18 #ifndef JOINT_STATES_CONVERTER_HPP 19 #define JOINT_STATES_CONVERTER_HPP 25 #include "../tools/robot_description.hpp" 32 #include <sensor_msgs/JointState.h> 44 typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) >
Callback_t;
48 typedef std::map<std::string, urdf::JointMimicSharedPtr>
MimicMap;
55 virtual void reset( );
59 void callAll(
const std::vector<message_actions::MessageAction>& actions );
64 void addChildren(
const KDL::SegmentMap::const_iterator segment);
66 void setTransforms(
const std::map<std::string, double>& joint_positions,
const ros::Time& time,
const std::string& tf_prefix);
77 std::map<message_actions::MessageAction, Callback_t>
callbacks_;
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap
boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > Callback_t
std::map< message_actions::MessageAction, Callback_t > callbacks_
void setFixedTransforms(const std::string &tf_prefix, const ros::Time &time)
std::map< std::string, robot_state_publisher::SegmentPair > segments_
void addChildren(const KDL::SegmentMap::const_iterator segment)
sensor_msgs::JointState msg_joint_states_
boost::shared_ptr< tf2_ros::Buffer > BufferPtr
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::map< std::string, robot_state_publisher::SegmentPair > segments_fixed_
void setTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix)
std::vector< geometry_msgs::TransformStamped > tf_transforms_
JointStateConverter(const std::string &name, const float &frequency, const BufferPtr &tf2_buffer, const qi::SessionPtr &session)