This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Committer:
nucho
Date:
Wed Feb 29 23:02:12 2012 +0000
Revision:
4:2cbca0ac2569
Parent:
3:dff241b66f84

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 0:06fc856e99ca 1 //#define COMPILE_TIMETF_CODE_ROSSERIAL
nucho 0:06fc856e99ca 2 #ifdef COMPILE_TIMETF_CODE_ROSSERIAL
nucho 0:06fc856e99ca 3
nucho 0:06fc856e99ca 4 /*
nucho 0:06fc856e99ca 5 * rosserial Time and TF Example
nucho 0:06fc856e99ca 6 * Publishes a transform at current time
nucho 0:06fc856e99ca 7 */
nucho 0:06fc856e99ca 8
nucho 0:06fc856e99ca 9 #include "mbed.h"
nucho 0:06fc856e99ca 10 #include <ros.h>
nucho 0:06fc856e99ca 11 #include <ros/time.h>
nucho 3:dff241b66f84 12 #include <tf/transform_broadcaster.h>
nucho 0:06fc856e99ca 13
nucho 0:06fc856e99ca 14 ros::NodeHandle nh;
nucho 0:06fc856e99ca 15
nucho 0:06fc856e99ca 16 geometry_msgs::TransformStamped t;
nucho 0:06fc856e99ca 17 tf::TransformBroadcaster broadcaster;
nucho 0:06fc856e99ca 18
nucho 0:06fc856e99ca 19 char base_link[] = "/base_link";
nucho 0:06fc856e99ca 20 char odom[] = "/odom";
nucho 0:06fc856e99ca 21
nucho 0:06fc856e99ca 22 int main() {
nucho 0:06fc856e99ca 23 nh.initNode();
nucho 3:dff241b66f84 24 broadcaster.init(nh);
nucho 3:dff241b66f84 25
nucho 0:06fc856e99ca 26
nucho 0:06fc856e99ca 27 while (1) {
nucho 0:06fc856e99ca 28 t.header.frame_id = odom;
nucho 0:06fc856e99ca 29 t.child_frame_id = base_link;
nucho 0:06fc856e99ca 30 t.transform.translation.x = 1.0;
nucho 0:06fc856e99ca 31 t.transform.rotation.x = 0.0;
nucho 0:06fc856e99ca 32 t.transform.rotation.y = 0.0;
nucho 0:06fc856e99ca 33 t.transform.rotation.z = 0.0;
nucho 0:06fc856e99ca 34 t.transform.rotation.w = 1.0;
nucho 0:06fc856e99ca 35 t.header.stamp = nh.now();
nucho 0:06fc856e99ca 36 broadcaster.sendTransform(t);
nucho 0:06fc856e99ca 37 nh.spinOnce();
nucho 0:06fc856e99ca 38 wait_ms(10);
nucho 0:06fc856e99ca 39 }
nucho 0:06fc856e99ca 40 }
nucho 0:06fc856e99ca 41
nucho 0:06fc856e99ca 42 #endif