#include <joint_state.hpp>
|
typedef boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > | Callback_t |
|
typedef boost::shared_ptr< tf2_ros::Buffer > | BufferPtr |
|
|
void | addChildren (const KDL::SegmentMap::const_iterator segment) |
|
void | setTransforms (const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix) |
|
void | setFixedTransforms (const std::string &tf_prefix, const ros::Time &time) |
|
naoqi::converter::JointStateConverter::JointStateConverter |
( |
const std::string & |
name, |
|
|
const float & |
frequency, |
|
|
const BufferPtr & |
tf2_buffer, |
|
|
const qi::SessionPtr & |
session |
|
) |
| |
naoqi::converter::JointStateConverter::~JointStateConverter |
( |
| ) |
|
void naoqi::converter::JointStateConverter::addChildren |
( |
const KDL::SegmentMap::const_iterator |
segment | ) |
|
|
private |
blatently copied from robot state publisher
JOINT STATE PUBLISHER
ROBOT STATE PUBLISHER
ODOMETRY
void naoqi::converter::JointStateConverter::reset |
( |
| ) |
|
|
virtual |
void naoqi::converter::JointStateConverter::setFixedTransforms |
( |
const std::string & |
tf_prefix, |
|
|
const ros::Time & |
time |
|
) |
| |
|
private |
void naoqi::converter::JointStateConverter::setTransforms |
( |
const std::map< std::string, double > & |
joint_positions, |
|
|
const ros::Time & |
time, |
|
|
const std::string & |
tf_prefix |
|
) |
| |
|
private |
sensor_msgs::JointState naoqi::converter::JointStateConverter::msg_joint_states_ |
|
private |
qi::AnyObject naoqi::converter::JointStateConverter::p_motion_ |
|
private |
std::string naoqi::converter::JointStateConverter::robot_desc_ |
|
private |
Robot Description in xml format
std::map<std::string, robot_state_publisher::SegmentPair> naoqi::converter::JointStateConverter::segments_ |
|
private |
std::map<std::string, robot_state_publisher::SegmentPair> naoqi::converter::JointStateConverter::segments_fixed_ |
|
private |
BufferPtr naoqi::converter::JointStateConverter::tf2_buffer_ |
|
private |
std::vector<geometry_msgs::TransformStamped> naoqi::converter::JointStateConverter::tf_transforms_ |
|
private |
The documentation for this class was generated from the following files:
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/src/converters/joint_state.hpp
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/src/converters/joint_state.cpp