testdrive.cpp
Go to the documentation of this file.
1 
26 // testdrive.cpp : An example of how to use rosserial in Windows
27 //
28 
29 #include "stdafx.h"
30 #include <string>
31 #include <stdio.h>
32 #include "ros.h"
33 #include <geometry_msgs/Twist.h>
34 #include <windows.h>
35 
36 using std::string;
37 
38 int main (int argc, char *argv[])
39 {
40  ros::NodeHandle nh;
41  if (argc != 2)
42  {
43  printf ("Usage: testdrive host[:port]\n");
44  return 0;
45  }
46 
47  printf ("Connecting to server at %s\n", argv[1]);
48  nh.initNode (argv[1]);
49 
50  printf ("Advertising cmd_vel message\n");
51  geometry_msgs::Twist twist_msg;
52  ros::Publisher cmd_vel_pub ("cmd_vel", &twist_msg);
53  nh.advertise (cmd_vel_pub);
54 
55  printf ("Go robot go!\n");
56  while (1)
57  {
58  twist_msg.linear.x = 5.1;
59  twist_msg.linear.y = 0;
60  twist_msg.linear.z = 0;
61  twist_msg.angular.x = 0;
62  twist_msg.angular.y = 0;
63  twist_msg.angular.z = -1.8;
64  cmd_vel_pub.publish (&twist_msg);
65 
66  nh.spinOnce ();
67  Sleep (100);
68  }
69  return 0;
70 }
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char *argv[])
Definition: testdrive.cpp:38


rosserial_windows
Author(s): Kareem Shehata
autogenerated on Mon Jun 10 2019 14:53:50