Go to the documentation of this file.00001
00026
00027
00028
00029 #include "stdafx.h"
00030 #include <string>
00031 #include <stdio.h>
00032 #include "ros.h"
00033 #include <geometry_msgs/Twist.h>
00034 #include <windows.h>
00035
00036 using std::string;
00037
00038 int main (int argc, char *argv[])
00039 {
00040 ros::NodeHandle nh;
00041 if (argc != 2)
00042 {
00043 printf ("Usage: testdrive host[:port]\n");
00044 return 0;
00045 }
00046
00047 printf ("Connecting to server at %s\n", argv[1]);
00048 nh.initNode (argv[1]);
00049
00050 printf ("Advertising cmd_vel message\n");
00051 geometry_msgs::Twist twist_msg;
00052 ros::Publisher cmd_vel_pub ("cmd_vel", &twist_msg);
00053 nh.advertise (cmd_vel_pub);
00054
00055 printf ("Go robot go!\n");
00056 while (1)
00057 {
00058 twist_msg.linear.x = 5.1;
00059 twist_msg.linear.y = 0;
00060 twist_msg.linear.z = 0;
00061 twist_msg.angular.x = 0;
00062 twist_msg.angular.y = 0;
00063 twist_msg.angular.z = -1.8;
00064 cmd_vel_pub.publish (&twist_msg);
00065
00066 nh.spinOnce ();
00067 Sleep (100);
00068 }
00069 return 0;
00070 }