TimeTF.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial Time and TF Example
00003  * Publishes a transform at current time
00004  */
00005 
00006 #include "mbed.h"
00007 #include <ros.h>
00008 #include <ros/time.h>
00009 #include <tf/transform_broadcaster.h>
00010 
00011 ros::NodeHandle  nh;
00012 
00013 geometry_msgs::TransformStamped t;
00014 tf::TransformBroadcaster broadcaster;
00015 
00016 char base_link[] = "/base_link";
00017 char odom[] = "/odom";
00018 
00019 int main() {
00020     nh.initNode();
00021     broadcaster.init(nh);
00022 
00023 
00024     while (1) {
00025         t.header.frame_id = odom;
00026         t.child_frame_id = base_link;
00027         t.transform.translation.x = 1.0;
00028         t.transform.rotation.x = 0.0;
00029         t.transform.rotation.y = 0.0;
00030         t.transform.rotation.z = 0.0;
00031         t.transform.rotation.w = 1.0;
00032         t.header.stamp = nh.now();
00033         broadcaster.sendTransform(t);
00034         nh.spinOnce();
00035         wait_ms(10);
00036     }
00037 }
00038 


rosserial_mbed
Author(s): Gary Servin
autogenerated on Sat Oct 7 2017 03:08:46