tf2 component
This module was started to provide an interface between open_robots::pose_estimator and ROS tf. The goal was to display these pose/frame in rviz You need to connect each or_pose_estimator::state port to the multiple in or_pose_estimator::state (with a name) then you can add this Pose to tf (with its parent, its refresh period, etc. A similar mechanism has been setup for forces which get translated to ROS wrenchs, and speeds to ROS twist. They can then be displayed in the proper frame in rviz.
Ports
Poses (multiple in)
Data structure
|
The GenoM or_pose_estimators you want to push in ROS tf.
Forces (multiple in)
Data structure
|
Force ports we want to push as geometry_msgs/WrenchStamped.msg.
Speeds (multiple in)
Data structure
|
Twist ports we want to push as geometry_msgs/TwistStamped.msg.
OccupancyGrid (in)
Data structure
|
To visualise the map in rviz.
Services
AddOccupancyGrid (function)
Inputs
|
Throws
|
Add an OccupancyGrid (only one) ROS nav_msgs/OccupancyGrid.msg.
AddWrench (function)
Inputs
|
Throws
|
Add an OpenRobot wrench to be transformed in a ROS geometry_msgs/WrenchStamped.msg.
AddWrenchFromPose (function)
Inputs
|
Throws
|
Add an OpenRobot wrench to be transformed in a ROS geometry_msgs/WrenchStamped.msg.
AddTwist (function)
Inputs
|
Throws
|
Add an OpenRobot speed in a or_rigid_body::state to be transformed in a ROS geometry_msgs/TwistStamped.msg.
AddTwistFromPose (function)
Inputs
|
Throws
|
Add an OpenRobot Pose speed field to be transformed in a ROS geometry_msgs/TwistStamped.msg.
AddDynamicTF (function)
Inputs
|
Throws
|
Add a Pose to be broadcasted to TF2 at ms_period.
AddOdometry (function)
Inputs
|
Throws
|
Add an already existing Pose to be broadcasted as Odometry.msg .
SetOdometryDisplay (function)
Inputs
|
Throws
|
Silence or unsilence an odometry…
AddDynamicPosTF (function)
Inputs
|
Throws
|
Add a Position only (not att, like gps) Pose to be broadcasted to TF2 at ms_period.
Tasks
RGPPTF
Context
|
Throws
|