12 #include <std_msgs/String.h> 17 str_msg.data = msgdata;
27 vexroslog(
"\n\n\n\n\r\t\tROSserial for VEX Cortex V2 - June 2018 - START\n\n\n\n\n\r");
31 std_msgs::String str_msg;
39 char* msg = (
char*) malloc(20 *
sizeof(
char));
43 sprintf(msg,
"[%d] Hello there!!", (
int) millis());
44 loop(nh, chatter, str_msg, msg);
void publish(const boost::shared_ptr< M > &message) const
void loop(ros::NodeHandle &nh, ros::Publisher &p, std_msgs::String &str_msg, char *msgdata)
#define vexroslog(fmtstr,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)