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!

Committer:
akashvibhute
Date:
Sun Feb 15 10:54:04 2015 +0000
Revision:
0:cb1dffdc7d05
Error: ; "mbed::Stream::Stream(const mbed::Stream &)" (declared at <a href="#" onmousedown="mbed_doc_goto('/mbed_roshydro_test//extras/mbed_e188a91d3eaa/Stream.h', '59'); return false;">/extras/mbed_e188a91d3eaa/Stream.h:59</a>) is inaccessible in "ext

Who changed what in which revision?

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