Public Member Functions | Public Attributes
RosMsgTreeUtilities Class Reference

#include <RosMsgTreeUtilities.h>

Inheritance diagram for RosMsgTreeUtilities:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void getFrameAccs (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::FrameAcc > &frameaccs)
void getFrames (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::Frame > &frames)
 updates a map of all the frames in poseState with their new location and orientations
void getFrameVels (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::FrameVel > &framevels)
void loadFromFile (const std::string &fileName)
 loads a file which describes the kinematic tree and resets bases
 RosMsgTreeUtilities ()
bool setBaseFrame (const r2_msgs::StringArray &baseMsg)
 sets the base frame vector to valid base frames
bool setBaseFrame (std::string &baseMsg)
 sets the base frame vector to valid base frames

Public Attributes

std::vector< std::string > bases
std::vector< std::string > jointNames

Detailed Description

Definition at line 13 of file RosMsgTreeUtilities.h.


Constructor & Destructor Documentation

Definition at line 3 of file RosMsgTreeUtilities.cpp.


Member Function Documentation

void RosMsgTreeUtilities::getFrameAccs ( const r2_msgs::PoseState &  poseState,
const std::string &  base,
std::map< std::string, KDL::FrameAcc > &  frameaccs 
)

Definition at line 140 of file RosMsgTreeUtilities.cpp.

void RosMsgTreeUtilities::getFrames ( const r2_msgs::PoseState &  poseState,
const std::string &  base,
std::map< std::string, KDL::Frame > &  frames 
)

updates a map of all the frames in poseState with their new location and orientations

Parameters:
poseStatethe poseState calculated from forward kinematics
basethe base frame from which to calculate all the poses
framesthe output frame map

Definition at line 85 of file RosMsgTreeUtilities.cpp.

void RosMsgTreeUtilities::getFrameVels ( const r2_msgs::PoseState &  poseState,
const std::string &  base,
std::map< std::string, KDL::FrameVel > &  framevels 
)

Definition at line 106 of file RosMsgTreeUtilities.cpp.

void RosMsgTreeUtilities::loadFromFile ( const std::string &  fileName)

loads a file which describes the kinematic tree and resets bases

Parameters:
fileNamethe file that contains the description of the kinematic tree

Reimplemented from KdlTreeParser.

Definition at line 16 of file RosMsgTreeUtilities.cpp.

bool RosMsgTreeUtilities::setBaseFrame ( const r2_msgs::StringArray &  baseMsg)

sets the base frame vector to valid base frames

Parameters:
baseMsgthe base message received from the system
Returns:
false if unable to find base frame in current tree

check if bases have changed

clear bases

check to see if bases are valid

Definition at line 29 of file RosMsgTreeUtilities.cpp.

bool RosMsgTreeUtilities::setBaseFrame ( std::string &  baseMsg)

sets the base frame vector to valid base frames

Parameters:
baseMsgthe base message received from the system
Returns:
false if unable to find base frame in current tree

Definition at line 65 of file RosMsgTreeUtilities.cpp.


Member Data Documentation

std::vector<std::string> RosMsgTreeUtilities::bases

Definition at line 27 of file RosMsgTreeUtilities.h.

std::vector<std::string> RosMsgTreeUtilities::jointNames

Definition at line 28 of file RosMsgTreeUtilities.h.


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


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