This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.
Dependents: rosserial_mbed robot_S2
tests/array_test.cpp@3:1cf99502f396, 2011-11-12 (annotated)
- Committer:
- nucho
- Date:
- Sat Nov 12 23:54:45 2011 +0000
- Revision:
- 3:1cf99502f396
This program supported the revision of 167 of rosserial.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 3:1cf99502f396 | 1 | //#define COMPILE_ARRAY_CODE_RSOSSERIAL |
nucho | 3:1cf99502f396 | 2 | #ifdef COMPILE_ARRAY_CODE_RSOSSERIAL |
nucho | 3:1cf99502f396 | 3 | |
nucho | 3:1cf99502f396 | 4 | /* |
nucho | 3:1cf99502f396 | 5 | * rosserial::geometry_msgs::PoseArray Test |
nucho | 3:1cf99502f396 | 6 | * Sums an array, publishes sum |
nucho | 3:1cf99502f396 | 7 | */ |
nucho | 3:1cf99502f396 | 8 | #include "mbed.h" |
nucho | 3:1cf99502f396 | 9 | #include <ros.h> |
nucho | 3:1cf99502f396 | 10 | #include <geometry_msgs/Pose.h> |
nucho | 3:1cf99502f396 | 11 | #include <geometry_msgs/PoseArray.h> |
nucho | 3:1cf99502f396 | 12 | |
nucho | 3:1cf99502f396 | 13 | |
nucho | 3:1cf99502f396 | 14 | ros::NodeHandle nh; |
nucho | 3:1cf99502f396 | 15 | |
nucho | 3:1cf99502f396 | 16 | bool set_; |
nucho | 3:1cf99502f396 | 17 | DigitalOut myled(LED1); |
nucho | 3:1cf99502f396 | 18 | |
nucho | 3:1cf99502f396 | 19 | geometry_msgs::Pose sum_msg; |
nucho | 3:1cf99502f396 | 20 | ros::Publisher p("sum", &sum_msg); |
nucho | 3:1cf99502f396 | 21 | |
nucho | 3:1cf99502f396 | 22 | void messageCb(const geometry_msgs::PoseArray& msg) { |
nucho | 3:1cf99502f396 | 23 | sum_msg.position.x = 0; |
nucho | 3:1cf99502f396 | 24 | sum_msg.position.y = 0; |
nucho | 3:1cf99502f396 | 25 | sum_msg.position.z = 0; |
nucho | 3:1cf99502f396 | 26 | for (int i = 0; i < msg.poses_length; i++) { |
nucho | 3:1cf99502f396 | 27 | sum_msg.position.x += msg.poses[i].position.x; |
nucho | 3:1cf99502f396 | 28 | sum_msg.position.y += msg.poses[i].position.y; |
nucho | 3:1cf99502f396 | 29 | sum_msg.position.z += msg.poses[i].position.z; |
nucho | 3:1cf99502f396 | 30 | } |
nucho | 3:1cf99502f396 | 31 | myled = !myled; // blink the led |
nucho | 3:1cf99502f396 | 32 | } |
nucho | 3:1cf99502f396 | 33 | |
nucho | 3:1cf99502f396 | 34 | ros::Subscriber<geometry_msgs::PoseArray> s("poses",messageCb); |
nucho | 3:1cf99502f396 | 35 | |
nucho | 3:1cf99502f396 | 36 | int main() { |
nucho | 3:1cf99502f396 | 37 | nh.initNode(); |
nucho | 3:1cf99502f396 | 38 | nh.subscribe(s); |
nucho | 3:1cf99502f396 | 39 | nh.advertise(p); |
nucho | 3:1cf99502f396 | 40 | |
nucho | 3:1cf99502f396 | 41 | while (1) { |
nucho | 3:1cf99502f396 | 42 | p.publish(&sum_msg); |
nucho | 3:1cf99502f396 | 43 | nh.spinOnce(); |
nucho | 3:1cf99502f396 | 44 | wait_ms(10); |
nucho | 3:1cf99502f396 | 45 | } |
nucho | 3:1cf99502f396 | 46 | } |
nucho | 3:1cf99502f396 | 47 | #endif |