rosserial mbed for Float64MultiArray (In this program, the topic name is "chatter"). you need the node at PC who send Float64MultiArray (In this program, the topic name is "req". And the number of data is same as the returning data ("chatter", in this program, 5 data)). The example is written at comment.
Dependencies: mbed ros_lib_indigo
Fork of rosserial_mbed_hello_world_publisher by
main.cpp
- Committer:
- hirokimineshita
- Date:
- 2016-10-25
- Revision:
- 2:b740e3e4c6c9
- Parent:
- 1:c7411b1ccd0f
File content as of revision 2:b740e3e4c6c9:
/* * rosserial Publisher Example * Prints "hello world!" */ /* ROS node program #include <ros/ros.h> #include <std_msgs/Float64MultiArray.h> int main(int argc,char **argv){ ros::init(argc,argv,"serial_test"); ros::NodeHandle n; ros::Publisher req_pub=n.advertise<std_msgs::Float64MultiArray>("req", 1000); ros::Rate loop_rate(174); while (ros::ok()){ std_msgs::Float64MultiArray msg; msg.data.clear(); for(int i=0;i<5;i++)msg.data.push_back(0); req_pub.publish(msg); ROS_INFO("send"); ros::spinOnce(); loop_rate.sleep(); } return 0; } */ #include <ros.h> #include "mbed.h" #include <std_msgs/Float64MultiArray.h> //ROS Float32Multiarray messages ros::NodeHandle nh; std_msgs::Float64MultiArray send; ros::Publisher chatter("chatter", &send); //Functions void ros_callback( const std_msgs::Float64MultiArray& req); ros::Subscriber<std_msgs::Float64MultiArray> sub("req", ros_callback); DigitalOut led = LED1; double num=0; void setup() { // Serial.begin(115200); //ROS nh.getHardware()->setBaud(115200); nh.initNode(); nh.advertise(chatter); nh.subscribe(sub); send.data_length = 5; } void loop() { nh.spinOnce(); } void ros_callback( const std_msgs::Float64MultiArray& req){ send=req; num+=0.1; for(int i=0;i<5;i++)send.data[i]=num; chatter.publish(&send); led=!led; } int main(){ setup(); while(1)loop(); }