ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged

Dependencies:   rosserial_hydro

Library and program still under development!

examples/TimeTF.cpp

Committer:
akashvibhute
Date:
2015-02-15
Revision:
1:225298843679
Parent:
0:cb1dffdc7d05

File content as of revision 1:225298843679:

//#define COMPILE_TIMETF_CODE_ROSSERIAL
#ifdef COMPILE_TIMETF_CODE_ROSSERIAL

/*
 * rosserial Time and TF Example
 * Publishes a transform at current time
 */

#include "mbed.h"
#include <ros.h>
#include <ros/time.h>
#include <tf/transform_broadcaster.h>

ros::NodeHandle  nh;

geometry_msgs::TransformStamped t;
tf::TransformBroadcaster broadcaster;

char base_link[] = "/base_link";
char odom[] = "/odom";

int main() {
    nh.initNode();
    broadcaster.init(nh);


    while (1) {
        t.header.frame_id = odom;
        t.child_frame_id = base_link;
        t.transform.translation.x = 1.0;
        t.transform.rotation.x = 0.0;
        t.transform.rotation.y = 0.0;
        t.transform.rotation.z = 0.0;
        t.transform.rotation.w = 1.0;
        t.header.stamp = nh.now();
        broadcaster.sendTransform(t);
        nh.spinOnce();
        wait_ms(10);
    }
}

#endif