-
Notifications
You must be signed in to change notification settings - Fork 65
/
Copy pathsetVehicleVelocity.cpp
73 lines (61 loc) · 1.78 KB
/
setVehicleVelocity.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
/*
* 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 <nav_msgs/Odometry.h>
int main(int argc, char **argv) {
if (argc < 8) {
std::cerr << "USAGE: " << argv[0] << " <topic> <vx> <vy> <vz> <vroll> <vpitch> <vyaw>" << std::endl;
std::cerr << "units are displacement/simulated_time. Time scale to be implemented." << 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]);
//std::string nodeName=topic;
//nodeName.replace(0,1,"a");
ros::init(argc, argv, "setVehicleVelocity");
ros::NodeHandle nh;
ros::Publisher position_pub;
position_pub=nh.advertise<nav_msgs::Odometry>(topic,1);
ros::Rate r(25);
while (ros::ok()) {
nav_msgs::Odometry odom;
odom.pose.pose.position.x=0.0;
odom.pose.pose.position.y=0.0;
odom.pose.pose.position.z=0.0;
odom.pose.pose.orientation.x=0.0;
odom.pose.pose.orientation.y=0.0;
odom.pose.pose.orientation.z=0.0;
odom.pose.pose.orientation.w=1;
odom.twist.twist.linear.x=x;
odom.twist.twist.linear.y=y;
odom.twist.twist.linear.z=z;
odom.twist.twist.angular.x=roll;
odom.twist.twist.angular.y=pitch;
odom.twist.twist.angular.z=yaw;
for (int i=0; i<36; i++) {
odom.twist.covariance[i]=0;
odom.pose.covariance[i]=0;
}
position_pub.publish(odom);
ros::spinOnce();
r.sleep();
}
return 0;
}