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@1:c7411b1ccd0f, 2016-10-25 (annotated)
- Committer:
- hirokimineshita
- Date:
- Tue Oct 25 06:29:41 2016 +0000
- Revision:
- 1:c7411b1ccd0f
- Parent:
- 0:17fd7572aedb
- Child:
- 2:b740e3e4c6c9
first upload
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 | */ |
hirokimineshita | 1:c7411b1ccd0f | 5 | /* |
garyservin | 0:17fd7572aedb | 6 | #include"mbed.h" |
garyservin | 0:17fd7572aedb | 7 | #include <ros.h> |
garyservin | 0:17fd7572aedb | 8 | #include <std_msgs/String.h> |
garyservin | 0:17fd7572aedb | 9 | |
garyservin | 0:17fd7572aedb | 10 | ros::NodeHandle nh; |
garyservin | 0:17fd7572aedb | 11 | |
garyservin | 0:17fd7572aedb | 12 | std_msgs::String str_msg; |
garyservin | 0:17fd7572aedb | 13 | ros::Publisher chatter("chatter", &str_msg); |
garyservin | 0:17fd7572aedb | 14 | |
hirokimineshita | 1:c7411b1ccd0f | 15 | char hello[13] = "hello world0"; |
garyservin | 0:17fd7572aedb | 16 | |
garyservin | 0:17fd7572aedb | 17 | DigitalOut led = LED1; |
garyservin | 0:17fd7572aedb | 18 | |
garyservin | 0:17fd7572aedb | 19 | int main() { |
hirokimineshita | 1:c7411b1ccd0f | 20 | int num=0; |
hirokimineshita | 1:c7411b1ccd0f | 21 | nh.getHardware()->setBaud(115200); |
garyservin | 0:17fd7572aedb | 22 | nh.initNode(); |
garyservin | 0:17fd7572aedb | 23 | nh.advertise(chatter); |
garyservin | 0:17fd7572aedb | 24 | |
garyservin | 0:17fd7572aedb | 25 | while (1) { |
garyservin | 0:17fd7572aedb | 26 | led = !led; |
hirokimineshita | 1:c7411b1ccd0f | 27 | hello[11]=num+48; |
garyservin | 0:17fd7572aedb | 28 | str_msg.data = hello; |
garyservin | 0:17fd7572aedb | 29 | chatter.publish( &str_msg ); |
garyservin | 0:17fd7572aedb | 30 | nh.spinOnce(); |
hirokimineshita | 1:c7411b1ccd0f | 31 | wait_ms(2); |
hirokimineshita | 1:c7411b1ccd0f | 32 | num++; |
hirokimineshita | 1:c7411b1ccd0f | 33 | if(num>9)num=0; |
hirokimineshita | 1:c7411b1ccd0f | 34 | } |
hirokimineshita | 1:c7411b1ccd0f | 35 | } |
hirokimineshita | 1:c7411b1ccd0f | 36 | */ |
hirokimineshita | 1:c7411b1ccd0f | 37 | /* |
hirokimineshita | 1:c7411b1ccd0f | 38 | #include"mbed.h" |
hirokimineshita | 1:c7411b1ccd0f | 39 | #include <ros.h> |
hirokimineshita | 1:c7411b1ccd0f | 40 | #include <std_msgs/Float64MultiArray.h> |
hirokimineshita | 1:c7411b1ccd0f | 41 | |
hirokimineshita | 1:c7411b1ccd0f | 42 | ros::NodeHandle nh; |
hirokimineshita | 1:c7411b1ccd0f | 43 | |
hirokimineshita | 1:c7411b1ccd0f | 44 | std_msgs::Float64MultiArray str_msg; |
hirokimineshita | 1:c7411b1ccd0f | 45 | |
hirokimineshita | 1:c7411b1ccd0f | 46 | double data[5]={0.1,0.2,0.3,0.4,0}; |
hirokimineshita | 1:c7411b1ccd0f | 47 | |
hirokimineshita | 1:c7411b1ccd0f | 48 | DigitalOut led = LED1; |
hirokimineshita | 1:c7411b1ccd0f | 49 | |
hirokimineshita | 1:c7411b1ccd0f | 50 | int main() { |
hirokimineshita | 1:c7411b1ccd0f | 51 | nh.getHardware()->setBaud(115200); |
hirokimineshita | 1:c7411b1ccd0f | 52 | nh.initNode(); |
hirokimineshita | 1:c7411b1ccd0f | 53 | str_msg.layout.dim_length=1; |
hirokimineshita | 1:c7411b1ccd0f | 54 | str_msg.data_length=5; |
hirokimineshita | 1:c7411b1ccd0f | 55 | str_msg.layout.dim = (std_msgs::MultiArrayDimension *) |
hirokimineshita | 1:c7411b1ccd0f | 56 | malloc(sizeof(std_msgs::MultiArrayDimension) * 2); |
hirokimineshita | 1:c7411b1ccd0f | 57 | str_msg.layout.dim[0].label = "chatter"; |
hirokimineshita | 1:c7411b1ccd0f | 58 | str_msg.layout.dim[0].size = 5; |
hirokimineshita | 1:c7411b1ccd0f | 59 | str_msg.layout.dim[0].stride = 1*5; |
hirokimineshita | 1:c7411b1ccd0f | 60 | str_msg.layout.data_offset = 0; |
hirokimineshita | 1:c7411b1ccd0f | 61 | str_msg.data = (double *)malloc(sizeof(double)*5); |
hirokimineshita | 1:c7411b1ccd0f | 62 | ros::Publisher chatter("chatter", &str_msg); |
hirokimineshita | 1:c7411b1ccd0f | 63 | nh.advertise(chatter); |
hirokimineshita | 1:c7411b1ccd0f | 64 | while (1) { |
hirokimineshita | 1:c7411b1ccd0f | 65 | led = !led; |
hirokimineshita | 1:c7411b1ccd0f | 66 | data[4]+=0.1; |
hirokimineshita | 1:c7411b1ccd0f | 67 | for(int i=0;i<5;i++)str_msg.data[i] = data[i]; |
hirokimineshita | 1:c7411b1ccd0f | 68 | chatter.publish( &str_msg ); |
hirokimineshita | 1:c7411b1ccd0f | 69 | nh.spinOnce(); |
garyservin | 0:17fd7572aedb | 70 | wait_ms(1000); |
garyservin | 0:17fd7572aedb | 71 | } |
hirokimineshita | 1:c7411b1ccd0f | 72 | }*/ |
hirokimineshita | 1:c7411b1ccd0f | 73 | |
hirokimineshita | 1:c7411b1ccd0f | 74 | #include <ros.h> |
hirokimineshita | 1:c7411b1ccd0f | 75 | #include "mbed.h" |
hirokimineshita | 1:c7411b1ccd0f | 76 | #include <std_msgs/Float64MultiArray.h> |
hirokimineshita | 1:c7411b1ccd0f | 77 | |
hirokimineshita | 1:c7411b1ccd0f | 78 | //ROS Float32Multiarray messages |
hirokimineshita | 1:c7411b1ccd0f | 79 | ros::NodeHandle nh; |
hirokimineshita | 1:c7411b1ccd0f | 80 | std_msgs::Float64MultiArray send; |
hirokimineshita | 1:c7411b1ccd0f | 81 | ros::Publisher chatter("chatter", &send); |
hirokimineshita | 1:c7411b1ccd0f | 82 | |
hirokimineshita | 1:c7411b1ccd0f | 83 | //Functions |
hirokimineshita | 1:c7411b1ccd0f | 84 | void ros_callback( const std_msgs::Float64MultiArray& req); |
hirokimineshita | 1:c7411b1ccd0f | 85 | ros::Subscriber<std_msgs::Float64MultiArray> sub("req", ros_callback); |
hirokimineshita | 1:c7411b1ccd0f | 86 | |
hirokimineshita | 1:c7411b1ccd0f | 87 | DigitalOut led = LED1; |
hirokimineshita | 1:c7411b1ccd0f | 88 | double num=0; |
hirokimineshita | 1:c7411b1ccd0f | 89 | |
hirokimineshita | 1:c7411b1ccd0f | 90 | void setup() |
hirokimineshita | 1:c7411b1ccd0f | 91 | { |
hirokimineshita | 1:c7411b1ccd0f | 92 | // Serial.begin(115200); |
hirokimineshita | 1:c7411b1ccd0f | 93 | //ROS |
hirokimineshita | 1:c7411b1ccd0f | 94 | nh.getHardware()->setBaud(115200); |
hirokimineshita | 1:c7411b1ccd0f | 95 | nh.initNode(); |
hirokimineshita | 1:c7411b1ccd0f | 96 | nh.advertise(chatter); |
hirokimineshita | 1:c7411b1ccd0f | 97 | nh.subscribe(sub); |
hirokimineshita | 1:c7411b1ccd0f | 98 | |
hirokimineshita | 1:c7411b1ccd0f | 99 | send.data_length = 5; |
hirokimineshita | 1:c7411b1ccd0f | 100 | } |
hirokimineshita | 1:c7411b1ccd0f | 101 | |
hirokimineshita | 1:c7411b1ccd0f | 102 | void loop() |
hirokimineshita | 1:c7411b1ccd0f | 103 | { |
hirokimineshita | 1:c7411b1ccd0f | 104 | nh.spinOnce(); |
hirokimineshita | 1:c7411b1ccd0f | 105 | } |
hirokimineshita | 1:c7411b1ccd0f | 106 | |
hirokimineshita | 1:c7411b1ccd0f | 107 | void ros_callback( const std_msgs::Float64MultiArray& req){ |
hirokimineshita | 1:c7411b1ccd0f | 108 | send=req; |
hirokimineshita | 1:c7411b1ccd0f | 109 | num+=0.1; |
hirokimineshita | 1:c7411b1ccd0f | 110 | for(int i=0;i<5;i++)send.data[i]=num; |
hirokimineshita | 1:c7411b1ccd0f | 111 | chatter.publish(&send); |
hirokimineshita | 1:c7411b1ccd0f | 112 | led=!led; |
hirokimineshita | 1:c7411b1ccd0f | 113 | } |
hirokimineshita | 1:c7411b1ccd0f | 114 | |
hirokimineshita | 1:c7411b1ccd0f | 115 | int main(){ |
hirokimineshita | 1:c7411b1ccd0f | 116 | setup(); |
hirokimineshita | 1:c7411b1ccd0f | 117 | while(1)loop(); |
garyservin | 0:17fd7572aedb | 118 | } |