helloworld.cpp
Go to the documentation of this file.
1 /*
2  * rosserial Publisher Example for VEX Cortex
3  * Prints "hello world!"
4  */
5 
6 #include "ros_lib/ros.h"
7 #include "ros_lib/std_msgs/String.h"
8 
9 // this loop is run in setup function, which publishes at 50hz.
10 void loop(ros::NodeHandle & nh, ros::Publisher & p, std_msgs::String & str_msg, char* msgdata)
11 {
12  str_msg.data = msgdata;
13  p.publish( &str_msg );
14  nh.spinOnce();
15  pros::c::delay(20);
16 }
17 
18 // The setup function will start a publisher on the topic "chatter" and begin publishing there.
19 void setup()
20 {
21  // debug logging
22  // make a node handle object, string message, and publisher for that message.
23  ros::NodeHandle nh;
24  std_msgs::String str_msg;
25  ros::Publisher chatter("chatter\0", &str_msg);
26 
27  // set up rosserial, and prepare to publish the chatter message
28  nh.initNode();
29  nh.advertise(chatter);
30 
31  // message data variable.
32  char* msg = (char*) malloc(20 * sizeof(char));
33  while (1) {
34 
35  // send a message about the time!
36  sprintf(msg, "[%d] Hello there!!", (int) pros::c::millis());
37  loop(nh, chatter, str_msg, msg);
38  }
39 }
void publish(const boost::shared_ptr< M > &message) const
void loop(ros::NodeHandle &nh, ros::Publisher &p, std_msgs::String &str_msg, char *msgdata)
Definition: helloworld.cpp:10
void setup()
Definition: helloworld.cpp:19
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)


rosserial_vex_v5
Author(s): Cannon
autogenerated on Mon Jun 10 2019 14:53:48