Converting Datatypes
Description: This is a quick description of the changes in syntax for converting datatypes.
Tutorial Level: INTERMEDIATE
C++
tf
Hard coded methods for bullet to message only.
1 #include "tf/transform_datatypes.h"
2 btVector3 btv = btVector3(xvalues[i], yvalues[i], zvalues[i]);
3 geometry_msgs::Vector3 msgv;
4 vector3TFToMsg(btv, msgv);
tf2
Same result using bullet and message bindings:
1 #include "tf2_bullet/tf2_bullet.h"
2 #include "tf2_geometry_msgs/tf2_geometry_msgs.h"
3 tf2::Stamped<btVector3> b(btVector3(1,2,3), ros::Time(), "my_frame");
4 geometry_msgs::Vector3Stamped m;
5 tf2::convert(b, m);
Much more extensible to convert bullet to kdl:
1 #include "tf2_kdl/tf2_kdl.h"
2 #include "tf2_bullet/tf2_bullet.h"
3 tf2::Stamped<btVector3> b(btVector3(1,2,3), ros::Time(), "my_frame");
4 tf2::Stamped<KDL::Vector> k;
5 tf2::convert(b, k);