18 #ifndef JOINT_STATES_CONVERTER_HPP
19 #define JOINT_STATES_CONVERTER_HPP
25 #include "../tools/robot_description.hpp"
31 #include <sensor_msgs/JointState.h>
32 #include <robot_state_publisher/robot_state_publisher.h>
42 typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) >
Callback_t;
44 typedef boost::shared_ptr<tf2_ros::Buffer>
BufferPtr;
51 virtual void reset( );
55 void callAll(
const std::vector<message_actions::MessageAction>& actions );
60 void addChildren(
const KDL::SegmentMap::const_iterator segment);
62 void setTransforms(
const std::map<std::string, double>& joint_positions,
const ros::Time& time,
const std::string& tf_prefix);
72 std::map<message_actions::MessageAction, Callback_t>
callbacks_;
std::string name() const
Definition: converter_base.hpp:54
float frequency() const
Definition: converter_base.hpp:59
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: joint_state.cpp:71
MessageAction
Definition: message_actions.h:9
BufferPtr tf2_buffer_
Definition: joint_state.hpp:66
boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > Callback_t
Definition: joint_state.hpp:42
~JointStateConverter()
Definition: joint_state.cpp:50
qi::AnyObject p_motion_
Definition: joint_state.hpp:69
virtual void reset()
Definition: joint_state.cpp:55
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: joint_state.hpp:72
Definition: converter_base.hpp:40
void setFixedTransforms(const std::string &tf_prefix, const ros::Time &time)
Definition: joint_state.cpp:199
std::map< std::string, robot_state_publisher::SegmentPair > segments_
Definition: joint_state.hpp:61
void addChildren(const KDL::SegmentMap::const_iterator segment)
Definition: joint_state.cpp:227
sensor_msgs::JointState msg_joint_states_
Definition: joint_state.hpp:78
std::string robot_desc_
Definition: joint_state.hpp:75
boost::shared_ptr< tf2_ros::Buffer > BufferPtr
Definition: joint_state.hpp:44
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: joint_state.cpp:76
std::map< std::string, robot_state_publisher::SegmentPair > segments_fixed_
Definition: joint_state.hpp:61
Definition: joint_state.hpp:39
void setTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix)
Definition: joint_state.cpp:167
std::vector< geometry_msgs::TransformStamped > tf_transforms_
Definition: joint_state.hpp:81
JointStateConverter(const std::string &name, const float &frequency, const BufferPtr &tf2_buffer, const qi::SessionPtr &session)
Definition: joint_state.cpp:42