Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
naoqi::converter::JointStateConverter Class Reference

#include <joint_state.hpp>

Inheritance diagram for naoqi::converter::JointStateConverter:
Inheritance graph
[legend]

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::BufferBufferPtr
 
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_tcallbacks_
 
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::SegmentPairsegments_
 
std::map< std::string, robot_state_publisher::SegmentPairsegments_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::Robotrobot_
 
qi::SessionPtr session_
 

Detailed Description

Definition at line 41 of file converters/joint_state.hpp.

Member Typedef Documentation

Definition at line 46 of file converters/joint_state.hpp.

typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) > naoqi::converter::JointStateConverter::Callback_t
private

Definition at line 44 of file converters/joint_state.hpp.

typedef std::map<std::string, urdf::JointMimicSharedPtr> naoqi::converter::JointStateConverter::MimicMap
private

Definition at line 48 of file converters/joint_state.hpp.

Constructor & Destructor Documentation

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.

Member Function Documentation

void naoqi::converter::JointStateConverter::addChildren ( const KDL::SegmentMap::const_iterator  segment)
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.

void naoqi::converter::JointStateConverter::reset ( )
virtual

Definition at line 57 of file converters/joint_state.cpp.

void naoqi::converter::JointStateConverter::setFixedTransforms ( const std::string &  tf_prefix,
const ros::Time time 
)
private

Definition at line 239 of file converters/joint_state.cpp.

void naoqi::converter::JointStateConverter::setTransforms ( const std::map< std::string, double > &  joint_positions,
const ros::Time time,
const std::string &  tf_prefix 
)
private

Definition at line 207 of file converters/joint_state.cpp.

Member Data Documentation

std::map<message_actions::MessageAction, Callback_t> naoqi::converter::JointStateConverter::callbacks_
private

Registered Callbacks

Definition at line 77 of file converters/joint_state.hpp.

MimicMap naoqi::converter::JointStateConverter::mimic_
private

MimicJoint List

Definition at line 83 of file converters/joint_state.hpp.

sensor_msgs::JointState naoqi::converter::JointStateConverter::msg_joint_states_
private

JointState Message

Definition at line 86 of file converters/joint_state.hpp.

qi::AnyObject naoqi::converter::JointStateConverter::p_memory_
private

Definition at line 74 of file converters/joint_state.hpp.

qi::AnyObject naoqi::converter::JointStateConverter::p_motion_
private

Motion Proxy

Definition at line 73 of file converters/joint_state.hpp.

std::string naoqi::converter::JointStateConverter::robot_desc_
private

Robot Description in xml format

Definition at line 80 of file converters/joint_state.hpp.

std::map<std::string, robot_state_publisher::SegmentPair> naoqi::converter::JointStateConverter::segments_
private

Definition at line 65 of file converters/joint_state.hpp.

std::map<std::string, robot_state_publisher::SegmentPair> naoqi::converter::JointStateConverter::segments_fixed_
private

Definition at line 65 of file converters/joint_state.hpp.

BufferPtr naoqi::converter::JointStateConverter::tf2_buffer_
private

Global Shared tf2 buffer

Definition at line 70 of file converters/joint_state.hpp.

std::vector<geometry_msgs::TransformStamped> naoqi::converter::JointStateConverter::tf_transforms_
private

Transform Messages

Definition at line 89 of file converters/joint_state.hpp.


The documentation for this class was generated from the following files:


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26