-
Notifications
You must be signed in to change notification settings - Fork 65
/
Copy pathsetVehiclePose.cpp
76 lines (60 loc) · 1.66 KB
/
setVehiclePose.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
/*
* Copyright (c) 2013 University of Jaume-I.
* All rights reserved. This program and the accompanying materials
* are made available under the terms of the GNU Public License v3.0
* which accompanies this distribution, and is available at
* http://www.gnu.org/licenses/gpl.html
*
* Contributors:
* Mario Prats
* Javier Perez
*/
#include <stdlib.h>
#include <string.h>
//ROS
#include <ros/ros.h>
#include <geometry_msgs/Pose.h>
#include <osg/Quat>
#include <osg/Vec3d>
#include <osg/Matrix>
int main(int argc, char **argv) {
ros::init(argc, argv, "setVehiclePose");
ros::NodeHandle nh;
if (argc < 8) {
std::cerr << "USAGE: " << argv[0] << " <topic> <x> <y> <z> <roll> <pitch> <yaw>" << std::endl;
std::cerr << "units are in meters and radians." << std::endl;
return 0;
}
std::string topic(argv[1]);
double x=atof(argv[2]);
double y=atof(argv[3]);
double z=atof(argv[4]);
double roll=atof(argv[5]);
double pitch=atof(argv[6]);
double yaw=atof(argv[7]);
ros::Publisher position_pub;
position_pub=nh.advertise<geometry_msgs::Pose>(topic,1);
osg::Matrixd T, Rx, Ry, Rz, transform;
T.makeTranslate(x,y,z);
Rx.makeRotate(roll,1,0,0);
Ry.makeRotate(pitch,0,1,0);
Rz.makeRotate(yaw,0,0,1);
transform=Rz*Ry*Rx*T;
osg::Vec3d trans=transform.getTrans();
osg::Quat rot=transform.getRotate();
ros::Rate r(25);
while (ros::ok()) {
geometry_msgs::Pose pose;
pose.position.x=trans.x();
pose.position.y=trans.y();
pose.position.z=trans.z();
pose.orientation.x=rot.x();
pose.orientation.y=rot.y();
pose.orientation.z=rot.z();
pose.orientation.w=rot.w();
position_pub.publish(pose);
ros::spinOnce();
r.sleep();
}
return 0;
}