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@2:b740e3e4c6c9, 2016-10-25 (annotated)
- Committer:
- hirokimineshita
- Date:
- Tue Oct 25 07:12:07 2016 +0000
- Revision:
- 2:b740e3e4c6c9
- Parent:
- 1:c7411b1ccd0f
add ROS node program
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:17fd7572aedb | 1 | /* |
garyservin | 0:17fd7572aedb | 2 | * rosserial Publisher Example |
garyservin | 0:17fd7572aedb | 3 | * Prints "hello world!" |
garyservin | 0:17fd7572aedb | 4 | */ |
garyservin | 0:17fd7572aedb | 5 | |
hirokimineshita | 2:b740e3e4c6c9 | 6 | /* ROS node program |
hirokimineshita | 2:b740e3e4c6c9 | 7 | #include <ros/ros.h> |
hirokimineshita | 2:b740e3e4c6c9 | 8 | #include <std_msgs/Float64MultiArray.h> |
garyservin | 0:17fd7572aedb | 9 | |
hirokimineshita | 2:b740e3e4c6c9 | 10 | int main(int argc,char **argv){ |
hirokimineshita | 2:b740e3e4c6c9 | 11 | ros::init(argc,argv,"serial_test"); |
hirokimineshita | 2:b740e3e4c6c9 | 12 | ros::NodeHandle n; |
hirokimineshita | 2:b740e3e4c6c9 | 13 | ros::Publisher req_pub=n.advertise<std_msgs::Float64MultiArray>("req", 1000); |
garyservin | 0:17fd7572aedb | 14 | |
hirokimineshita | 2:b740e3e4c6c9 | 15 | ros::Rate loop_rate(174); |
hirokimineshita | 2:b740e3e4c6c9 | 16 | while (ros::ok()){ |
hirokimineshita | 2:b740e3e4c6c9 | 17 | std_msgs::Float64MultiArray msg; |
hirokimineshita | 2:b740e3e4c6c9 | 18 | msg.data.clear(); |
hirokimineshita | 2:b740e3e4c6c9 | 19 | for(int i=0;i<5;i++)msg.data.push_back(0); |
hirokimineshita | 2:b740e3e4c6c9 | 20 | req_pub.publish(msg); |
hirokimineshita | 2:b740e3e4c6c9 | 21 | ROS_INFO("send"); |
hirokimineshita | 2:b740e3e4c6c9 | 22 | ros::spinOnce(); |
hirokimineshita | 2:b740e3e4c6c9 | 23 | loop_rate.sleep(); |
hirokimineshita | 2:b740e3e4c6c9 | 24 | } |
hirokimineshita | 2:b740e3e4c6c9 | 25 | return 0; |
hirokimineshita | 1:c7411b1ccd0f | 26 | } |
hirokimineshita | 1:c7411b1ccd0f | 27 | */ |
hirokimineshita | 1:c7411b1ccd0f | 28 | |
hirokimineshita | 1:c7411b1ccd0f | 29 | #include <ros.h> |
hirokimineshita | 1:c7411b1ccd0f | 30 | #include "mbed.h" |
hirokimineshita | 1:c7411b1ccd0f | 31 | #include <std_msgs/Float64MultiArray.h> |
hirokimineshita | 1:c7411b1ccd0f | 32 | |
hirokimineshita | 1:c7411b1ccd0f | 33 | //ROS Float32Multiarray messages |
hirokimineshita | 1:c7411b1ccd0f | 34 | ros::NodeHandle nh; |
hirokimineshita | 1:c7411b1ccd0f | 35 | std_msgs::Float64MultiArray send; |
hirokimineshita | 1:c7411b1ccd0f | 36 | ros::Publisher chatter("chatter", &send); |
hirokimineshita | 1:c7411b1ccd0f | 37 | |
hirokimineshita | 1:c7411b1ccd0f | 38 | //Functions |
hirokimineshita | 1:c7411b1ccd0f | 39 | void ros_callback( const std_msgs::Float64MultiArray& req); |
hirokimineshita | 1:c7411b1ccd0f | 40 | ros::Subscriber<std_msgs::Float64MultiArray> sub("req", ros_callback); |
hirokimineshita | 1:c7411b1ccd0f | 41 | |
hirokimineshita | 1:c7411b1ccd0f | 42 | DigitalOut led = LED1; |
hirokimineshita | 1:c7411b1ccd0f | 43 | double num=0; |
hirokimineshita | 1:c7411b1ccd0f | 44 | |
hirokimineshita | 1:c7411b1ccd0f | 45 | void setup() |
hirokimineshita | 1:c7411b1ccd0f | 46 | { |
hirokimineshita | 1:c7411b1ccd0f | 47 | // Serial.begin(115200); |
hirokimineshita | 1:c7411b1ccd0f | 48 | //ROS |
hirokimineshita | 1:c7411b1ccd0f | 49 | nh.getHardware()->setBaud(115200); |
hirokimineshita | 1:c7411b1ccd0f | 50 | nh.initNode(); |
hirokimineshita | 1:c7411b1ccd0f | 51 | nh.advertise(chatter); |
hirokimineshita | 1:c7411b1ccd0f | 52 | nh.subscribe(sub); |
hirokimineshita | 1:c7411b1ccd0f | 53 | |
hirokimineshita | 1:c7411b1ccd0f | 54 | send.data_length = 5; |
hirokimineshita | 1:c7411b1ccd0f | 55 | } |
hirokimineshita | 1:c7411b1ccd0f | 56 | |
hirokimineshita | 1:c7411b1ccd0f | 57 | void loop() |
hirokimineshita | 1:c7411b1ccd0f | 58 | { |
hirokimineshita | 1:c7411b1ccd0f | 59 | nh.spinOnce(); |
hirokimineshita | 1:c7411b1ccd0f | 60 | } |
hirokimineshita | 1:c7411b1ccd0f | 61 | |
hirokimineshita | 1:c7411b1ccd0f | 62 | void ros_callback( const std_msgs::Float64MultiArray& req){ |
hirokimineshita | 1:c7411b1ccd0f | 63 | send=req; |
hirokimineshita | 1:c7411b1ccd0f | 64 | num+=0.1; |
hirokimineshita | 1:c7411b1ccd0f | 65 | for(int i=0;i<5;i++)send.data[i]=num; |
hirokimineshita | 1:c7411b1ccd0f | 66 | chatter.publish(&send); |
hirokimineshita | 1:c7411b1ccd0f | 67 | led=!led; |
hirokimineshita | 1:c7411b1ccd0f | 68 | } |
hirokimineshita | 1:c7411b1ccd0f | 69 | |
hirokimineshita | 1:c7411b1ccd0f | 70 | int main(){ |
hirokimineshita | 1:c7411b1ccd0f | 71 | setup(); |
hirokimineshita | 1:c7411b1ccd0f | 72 | while(1)loop(); |
garyservin | 0:17fd7572aedb | 73 | } |