Public Member Functions | Private Types | Private Attributes
RosMsgTreeFk Class Reference

#include <RosMsgTreeFk.h>

Inheritance diagram for RosMsgTreeFk:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getPoseState (const sensor_msgs::JointState &jointState, r2_msgs::PoseState &poseState)
virtual void initialize ()
 initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded
void reset ()
 RosMsgTreeFk ()
 ~RosMsgTreeFk ()

Private Types

typedef std::map< std::string,
std::pair< ros::Time,
geometry_msgs::Twist > > 
prevVel_type

Private Attributes

std::vector< std::string > jointNames
KDL::JntArrayVel joints
std::map< std::string,
KDL::FrameVel
poseMap
prevVel_type prevVel

Detailed Description

Definition at line 15 of file RosMsgTreeFk.h.


Member Typedef Documentation

typedef std::map<std::string, std::pair<ros::Time, geometry_msgs::Twist> > RosMsgTreeFk::prevVel_type [private]

Definition at line 34 of file RosMsgTreeFk.h.


Constructor & Destructor Documentation

Definition at line 3 of file RosMsgTreeFk.cpp.

Definition at line 8 of file RosMsgTreeFk.cpp.


Member Function Documentation

bool RosMsgTreeFk::getPoseState ( const sensor_msgs::JointState &  jointState,
r2_msgs::PoseState &  poseState 
)

get joints

get poses

convert to message

Definition at line 26 of file RosMsgTreeFk.cpp.

void RosMsgTreeFk::initialize ( ) [virtual]

initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded

Reimplemented from KdlTreeFk.

Definition at line 12 of file RosMsgTreeFk.cpp.

void RosMsgTreeFk::reset ( ) [inline]

Definition at line 21 of file RosMsgTreeFk.h.


Member Data Documentation

std::vector<std::string> RosMsgTreeFk::jointNames [private]

Definition at line 36 of file RosMsgTreeFk.h.

Definition at line 37 of file RosMsgTreeFk.h.

std::map<std::string, KDL::FrameVel> RosMsgTreeFk::poseMap [private]

Definition at line 38 of file RosMsgTreeFk.h.

Definition at line 35 of file RosMsgTreeFk.h.


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


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:54