xb3_frame_tf_broadcaster.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <tf/transform_broadcaster.h>
3 
4 int main(int argc, char** argv)
5 {
6  ros::init(argc, argv, "my_tf_broadcaster");
7  ros::NodeHandle node;
8 
9  tf::TransformBroadcaster br;
10  tf::Transform transform;
11 
12  ros::Rate rate(10.0);
13 
14  while (node.ok())
15  {
16  transform.setOrigin( tf::Vector3( -1.8375, 0.2646, 1.1118) );
17 
18 
19  tf::Matrix3x3 tf3d;
20  tf3d.setValue( -0.0184, -0.1384, 0.9902,
21  -0.9998, 0.0052, -0.0179,
22  -0.0027, -0.9904, -0.1384);
23 
24  tf::Quaternion tfqt;
25  tf3d.getRotation(tfqt);
26 
27 // transform.setRotation( tf::Quaternion(1.597001304715086, -0.8908563685714233, -1.581197539311177) );
28 
29  transform.setRotation(tfqt);
30 
31  br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "atc/vehicle/center_bumper", "atc/vehicle/carrot1"));
32  rate.sleep();
33  }
34 
35  return 0;
36 };
int main(int argc, char **argv)


multimodal_pedestrian_detect
Author(s): Rui Azevedo
autogenerated on Mon Mar 2 2015 01:32:27