helloworld.cpp
Go to the documentation of this file.
1 /*
2  * rosserial Publisher Example for VEX Cortex
3  * Prints "hello world!"
4  *
5  *
6  *
7  * Note: defining rosserial objects on the global scope will cause segmentation faults.
8  * put variables in functons.
9  */
10 
11 #include <ros.h>
12 #include <std_msgs/String.h>
13 
14 // this loop is run in setup function, which publishes at 50hz.
15 inline void loop(ros::NodeHandle & nh, ros::Publisher & p, std_msgs::String & str_msg, char* msgdata)
16 {
17  str_msg.data = msgdata;
18  p.publish( &str_msg );
19  nh.spinOnce();
20  delay(20);
21 }
22 
23 // The setup function will start a publisher on the topic "chatter" and begin publishing there.
24 inline void setup()
25 {
26  // debug logging
27  vexroslog("\n\n\n\n\r\t\tROSserial for VEX Cortex V2 - June 2018 - START\n\n\n\n\n\r");
28 
29  // make a node handle object, string message, and publisher for that message.
30  ros::NodeHandle nh;
31  std_msgs::String str_msg;
32  ros::Publisher chatter("chatter\0", &str_msg);
33 
34  // set up rosserial, and prepare to publish the chatter message
35  nh.initNode();
36  nh.advertise(chatter);
37 
38  // message data variable.
39  char* msg = (char*) malloc(20 * sizeof(char));
40  while (1) {
41 
42  // send a message about the time!
43  sprintf(msg, "[%d] Hello there!!", (int) millis());
44  loop(nh, chatter, str_msg, msg);
45  }
46 }
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:15
#define vexroslog(fmtstr,...)
Definition: logger.h:25
void setup()
Definition: helloworld.cpp:24
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)


rosserial_vex_cortex
Author(s): Cannon
autogenerated on Fri Jun 7 2019 22:03:06