TimeTF.cpp
Go to the documentation of this file.
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 
12 
13 geometry_msgs::TransformStamped t;
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 }
38 
tf::TransformBroadcaster broadcaster
Definition: TimeTF.cpp:14
geometry_msgs::TransformStamped t
Definition: TimeTF.cpp:13
char odom[]
Definition: TimeTF.cpp:17
void sendTransform(const StampedTransform &transform)
int main()
Definition: TimeTF.cpp:19
char base_link[]
Definition: TimeTF.cpp:16
ros::NodeHandle nh
Definition: TimeTF.cpp:11


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48