(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Time and TF

Description: This tutorial shows how to use ros::Time and TF to create a tf publisher on MBED.

Keywords: MBED, rosserial, serial

Tutorial Level: INTERMEDIATE

Next Tutorial: Measuring Temperature

  Show EOL distros: 

Using Time and TF on MBED

The rosserial_mbed package contains libraries for generating timestamps on MBED which are synchronized with the computer on which the roscore instance is running. This tutorial shows how to access time, using an example of publishing a tf transform.

The Code

Open the Time and TF example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the TimeTF.cpp file in your favorite text editor:

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

The Code Explained

Now, let's break the code down.

   6 #include "mbed.h"
   7 

We need to include the mbed.h for every MBED program.

   7 #include <ros.h>
   8 #include <ros/time.h>
   9 #include <tf/transform_broadcaster.h>
  10 
  11 ros::NodeHandle  nh;

We need to include our typical ROS stuff.

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

Next, we instantiate a TransformStamped message to use, and a broadcaster. We also need to specify the names of the frames we are publishing a transform for, and the transform broadcaster.

  20     nh.initNode();
  21     broadcaster.init(nh);

Inside the main function, we have to call init() on the TransformBroadcaster with the node handle as a parameter. Without doing this, the broadcaster will not publish correctly.

  25         t.header.frame_id = odom;
  26         t.child_frame_id = base_link;
  27         t.transform.translation.x = 1.0;
  28         t.transform.rotation.x = 0.0;
  29         t.transform.rotation.y = 0.0;
  30         t.transform.rotation.z = 0.0;
  31         t.transform.rotation.w = 1.0;

Then, inside the main function there's a loop in which we fill in the fields of our transform. The frame IDs are set to the correct string names, and the values of the translation and rotation are set.

  32         t.header.stamp = nh.now();

Calling nh.now() returns the current time, as a ros::Time instance, just like when using roscpp's ros::Time::now().

  33         broadcaster.sendTransform(t);
  34         nh.spinOnce();
  35         wait_ms(10);
  36     }
  37 }

Finally, we publish the transform, and then spinOnce and wait a bit before doing it again. Transforms should always be published at a regular rate, although usually the data fields will be filled in from real data.

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Running the Code

Now, launch the roscore in a new terminal window:

roscore

Next, run the rosserial client application that forwards your mbed messages to the rest of ROS. Make sure to use the correct serial port:

rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0

rosrun rosserial_python serial_node.py /dev/ttyUSB0

Finally, you can check the transform using:

rosrun tf tf_echo odom base_link

Or, by running:

rosrun tf view_frames

Further Reading

Please see rosserial/Overview for more information using Time instances.

Wiki: rosserial_mbed/Tutorials/Time and TF (last edited 2015-11-20 21:07:07 by AlexisPojomovsky)