Public Member Functions | Static Public Attributes | Private Attributes | List of all members
pal::Motion Class Reference

#include <motion_model.h>

Public Member Functions

bool addGroupToGroup (const std::string &group, const std::string &subgroup)
 
void addJointModel (const std::string &joint_name, const JointModel &joint_model)
 
void addJointToGroup (const std::string &group, const std::string &joint)
 
void addKeyFrame (const sensor_msgs::JointStateConstPtr &msg, float time_increment=DEFAULT_TIME)
 
double changeJoint (int frame, const std::string &joint_name, double position)
 
void changeTime (int frame, float time_increment)
 
void copyFrame (int frame, int new_frame_pos=-1)
 
void extendFrames (const sensor_msgs::JointStateConstPtr &msg)
 
std::vector< std::string > getAvailableJoints ()
 
const std::string & getCurrentGroup ()
 
std::vector< std::string > getExtraJoints ()
 
std::vector< std::string > getJointGroups ()
 
std::vector< std::string > getJoints () const
 
const KeyFramegetKeyFrame (int i) const
 
const std::vector< KeyFramegetKeyframes () const
 
const KeyFramegetLastKeyFrame () const
 
const std::string & getParamName () const
 
bool isJointUsed (const std::string &joint_name) const
 
bool jointsLoaded ()
 
void loadFrame (int frame) const
 
void loadYAML (double downshift) const
 
 Motion (const std::string &robot_description, const std::string &robot_description_semantic, const std::vector< std::string > &extra_joints)
 
 Motion (XmlRpc::XmlRpcValue &param, const std::string &robot_description, const std::string &robot_description_semantic, const std::vector< std::string > &extra_joints)
 
PrintMotion print (double downshift=1.0) const
 
PrintMotion print (const std::string &name, const std::string &usage, const std::string &description, double downshift=1.0) const
 
void removeAllKeyFrames ()
 
void removeKeyFrame (int frame)
 
bool setCurrentGroup (const std::string &group)
 
bool setExtraJointUsedState (const std::string &name, bool used)
 
void setMotionGroups (const std::string &robot_description, const std::string &robot_description_semantic)
 
void setParamName ()
 
std::size_t size () const
 
void updateKeyFrame (const sensor_msgs::JointStateConstPtr &msg, int frame)
 

Static Public Attributes

static const float DEFAULT_TIME = 5.0
 

Private Attributes

std::unordered_map< std::string, bool > extra_joints_
 
std::string group_used_
 
std::unordered_map< std::string, std::vector< std::string > > joint_groups_
 
std::unordered_map< std::string, JointModeljoint_models_
 
std::vector< KeyFramekeyframes_
 
std::string tmp_name_
 

Detailed Description

The Motion class represents a complex motion of the robot, encoded as a sequence of Keyframes at specific times

Definition at line 138 of file motion_model.h.

Constructor & Destructor Documentation

◆ Motion() [1/2]

pal::Motion::Motion ( const std::string &  robot_description,
const std::string &  robot_description_semantic,
const std::vector< std::string > &  extra_joints 
)

Definition at line 122 of file motion_model.cpp.

◆ Motion() [2/2]

pal::Motion::Motion ( XmlRpc::XmlRpcValue param,
const std::string &  robot_description,
const std::string &  robot_description_semantic,
const std::vector< std::string > &  extra_joints 
)

Definition at line 154 of file motion_model.cpp.

Member Function Documentation

◆ addGroupToGroup()

bool pal::Motion::addGroupToGroup ( const std::string &  group,
const std::string &  subgroup 
)

Definition at line 522 of file motion_model.cpp.

◆ addJointModel()

void pal::Motion::addJointModel ( const std::string &  joint_name,
const JointModel joint_model 
)

Definition at line 389 of file motion_model.cpp.

◆ addJointToGroup()

void pal::Motion::addJointToGroup ( const std::string &  group,
const std::string &  joint 
)

Definition at line 514 of file motion_model.cpp.

◆ addKeyFrame()

void pal::Motion::addKeyFrame ( const sensor_msgs::JointStateConstPtr &  msg,
float  time_increment = DEFAULT_TIME 
)

Definition at line 353 of file motion_model.cpp.

◆ changeJoint()

double pal::Motion::changeJoint ( int  frame,
const std::string &  joint_name,
double  position 
)

Definition at line 405 of file motion_model.cpp.

◆ changeTime()

void pal::Motion::changeTime ( int  frame,
float  time_increment 
)

Definition at line 394 of file motion_model.cpp.

◆ copyFrame()

void pal::Motion::copyFrame ( int  frame,
int  new_frame_pos = -1 
)

Definition at line 436 of file motion_model.cpp.

◆ extendFrames()

void pal::Motion::extendFrames ( const sensor_msgs::JointStateConstPtr &  msg)

Definition at line 497 of file motion_model.cpp.

◆ getAvailableJoints()

std::vector<std::string> pal::Motion::getAvailableJoints ( )
inline

Definition at line 273 of file motion_model.h.

◆ getCurrentGroup()

const std::string& pal::Motion::getCurrentGroup ( )
inline

Definition at line 214 of file motion_model.h.

◆ getExtraJoints()

std::vector<std::string> pal::Motion::getExtraJoints ( )
inline

Definition at line 263 of file motion_model.h.

◆ getJointGroups()

std::vector<std::string> pal::Motion::getJointGroups ( )
inline

Definition at line 253 of file motion_model.h.

◆ getJoints()

std::vector<std::string> pal::Motion::getJoints ( ) const
inline

Definition at line 186 of file motion_model.h.

◆ getKeyFrame()

const KeyFrame& pal::Motion::getKeyFrame ( int  i) const
inline

Definition at line 182 of file motion_model.h.

◆ getKeyframes()

const std::vector<KeyFrame> pal::Motion::getKeyframes ( ) const
inline

Definition at line 210 of file motion_model.h.

◆ getLastKeyFrame()

const KeyFrame& pal::Motion::getLastKeyFrame ( ) const
inline

Definition at line 178 of file motion_model.h.

◆ getParamName()

const std::string& pal::Motion::getParamName ( ) const
inline

Definition at line 170 of file motion_model.h.

◆ isJointUsed()

bool pal::Motion::isJointUsed ( const std::string &  joint_name) const
inline

Definition at line 230 of file motion_model.h.

◆ jointsLoaded()

bool pal::Motion::jointsLoaded ( )
inline

Definition at line 174 of file motion_model.h.

◆ loadFrame()

void pal::Motion::loadFrame ( int  frame) const

Definition at line 455 of file motion_model.cpp.

◆ loadYAML()

void pal::Motion::loadYAML ( double  downshift) const

Definition at line 476 of file motion_model.cpp.

◆ print() [1/2]

PrintMotion pal::Motion::print ( double  downshift = 1.0) const

Definition at line 541 of file motion_model.cpp.

◆ print() [2/2]

PrintMotion pal::Motion::print ( const std::string &  name,
const std::string &  usage,
const std::string &  description,
double  downshift = 1.0 
) const

Definition at line 551 of file motion_model.cpp.

◆ removeAllKeyFrames()

void pal::Motion::removeAllKeyFrames ( )

Definition at line 546 of file motion_model.cpp.

◆ removeKeyFrame()

void pal::Motion::removeKeyFrame ( int  frame)

Definition at line 431 of file motion_model.cpp.

◆ setCurrentGroup()

bool pal::Motion::setCurrentGroup ( const std::string &  group)
inline

Definition at line 218 of file motion_model.h.

◆ setExtraJointUsedState()

bool pal::Motion::setExtraJointUsedState ( const std::string &  name,
bool  used 
)
inline

Definition at line 241 of file motion_model.h.

◆ setMotionGroups()

void pal::Motion::setMotionGroups ( const std::string &  robot_description,
const std::string &  robot_description_semantic 
)

Definition at line 232 of file motion_model.cpp.

◆ setParamName()

void pal::Motion::setParamName ( )

Definition at line 341 of file motion_model.cpp.

◆ size()

std::size_t pal::Motion::size ( ) const
inline

Definition at line 206 of file motion_model.h.

◆ updateKeyFrame()

void pal::Motion::updateKeyFrame ( const sensor_msgs::JointStateConstPtr &  msg,
int  frame 
)

Definition at line 373 of file motion_model.cpp.

Member Data Documentation

◆ DEFAULT_TIME

const float pal::Motion::DEFAULT_TIME = 5.0
static

Definition at line 141 of file motion_model.h.

◆ extra_joints_

std::unordered_map<std::string, bool> pal::Motion::extra_joints_
private

Definition at line 300 of file motion_model.h.

◆ group_used_

std::string pal::Motion::group_used_
private

Definition at line 301 of file motion_model.h.

◆ joint_groups_

std::unordered_map<std::string, std::vector<std::string> > pal::Motion::joint_groups_
private

Definition at line 299 of file motion_model.h.

◆ joint_models_

std::unordered_map<std::string, JointModel> pal::Motion::joint_models_
private

Definition at line 302 of file motion_model.h.

◆ keyframes_

std::vector<KeyFrame> pal::Motion::keyframes_
private

Definition at line 298 of file motion_model.h.

◆ tmp_name_

std::string pal::Motion::tmp_name_
private

Definition at line 297 of file motion_model.h.


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


play_motion_builder
Author(s):
autogenerated on Mon Feb 28 2022 23:13:39