#include <joint_state.hpp>

Public Member Functions | |
| void | callAll (const std::vector< message_actions::MessageAction > &actions) |
| JointStateConverter (const std::string &name, const float &frequency, const BufferPtr &tf2_buffer, const qi::SessionPtr &session) | |
| void | registerCallback (const message_actions::MessageAction action, Callback_t cb) |
| virtual void | reset () |
| ~JointStateConverter () | |
Public Member Functions inherited from naoqi::converter::BaseConverter< JointStateConverter > | |
| BaseConverter (const std::string &name, float frequency, qi::SessionPtr session) | |
| float | frequency () const |
| std::string | name () const |
| virtual | ~BaseConverter () |
Private Types | |
| typedef boost::shared_ptr< tf2_ros::Buffer > | BufferPtr |
| typedef boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > | Callback_t |
| typedef std::map< std::string, urdf::JointMimicSharedPtr > | MimicMap |
Private Member Functions | |
| void | addChildren (const KDL::SegmentMap::const_iterator segment) |
| void | setFixedTransforms (const std::string &tf_prefix, const ros::Time &time) |
| void | setTransforms (const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix) |
Private Attributes | |
| std::map< message_actions::MessageAction, Callback_t > | callbacks_ |
| MimicMap | mimic_ |
| sensor_msgs::JointState | msg_joint_states_ |
| qi::AnyObject | p_memory_ |
| qi::AnyObject | p_motion_ |
| std::string | robot_desc_ |
| std::map< std::string, robot_state_publisher::SegmentPair > | segments_ |
| std::map< std::string, robot_state_publisher::SegmentPair > | segments_fixed_ |
| BufferPtr | tf2_buffer_ |
| std::vector< geometry_msgs::TransformStamped > | tf_transforms_ |
Additional Inherited Members | |
Protected Attributes inherited from naoqi::converter::BaseConverter< JointStateConverter > | |
| float | frequency_ |
| std::string | name_ |
| bool | record_enabled_ |
| const robot::Robot & | robot_ |
| qi::SessionPtr | session_ |
Definition at line 41 of file converters/joint_state.hpp.
Definition at line 46 of file converters/joint_state.hpp.
|
private |
Definition at line 44 of file converters/joint_state.hpp.
|
private |
Definition at line 48 of file converters/joint_state.hpp.
| naoqi::converter::JointStateConverter::JointStateConverter | ( | const std::string & | name, |
| const float & | frequency, | ||
| const BufferPtr & | tf2_buffer, | ||
| const qi::SessionPtr & | session | ||
| ) |
Definition at line 43 of file converters/joint_state.cpp.
| naoqi::converter::JointStateConverter::~JointStateConverter | ( | ) |
Definition at line 52 of file converters/joint_state.cpp.
|
private |
blatently copied from robot state publisher
Definition at line 267 of file converters/joint_state.cpp.
| void naoqi::converter::JointStateConverter::callAll | ( | const std::vector< message_actions::MessageAction > & | actions | ) |
JOINT STATE PUBLISHER
ROBOT STATE PUBLISHER
ODOMETRY
Definition at line 87 of file converters/joint_state.cpp.
| void naoqi::converter::JointStateConverter::registerCallback | ( | const message_actions::MessageAction | action, |
| Callback_t | cb | ||
| ) |
Definition at line 82 of file converters/joint_state.cpp.
|
virtual |
Definition at line 57 of file converters/joint_state.cpp.
|
private |
Definition at line 239 of file converters/joint_state.cpp.
|
private |
Definition at line 207 of file converters/joint_state.cpp.
|
private |
Registered Callbacks
Definition at line 77 of file converters/joint_state.hpp.
|
private |
MimicJoint List
Definition at line 83 of file converters/joint_state.hpp.
|
private |
JointState Message
Definition at line 86 of file converters/joint_state.hpp.
|
private |
Definition at line 74 of file converters/joint_state.hpp.
|
private |
Motion Proxy
Definition at line 73 of file converters/joint_state.hpp.
|
private |
Robot Description in xml format
Definition at line 80 of file converters/joint_state.hpp.
|
private |
Definition at line 65 of file converters/joint_state.hpp.
|
private |
Definition at line 65 of file converters/joint_state.hpp.
|
private |
Global Shared tf2 buffer
Definition at line 70 of file converters/joint_state.hpp.
|
private |
Transform Messages
Definition at line 89 of file converters/joint_state.hpp.