#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 KeyFrame & | getKeyFrame (int i) const |
const std::vector< KeyFrame > | getKeyframes () const |
const KeyFrame & | getLastKeyFrame () 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 ¶m, 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, JointModel > | joint_models_ |
std::vector< KeyFrame > | keyframes_ |
std::string | tmp_name_ |
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.
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.
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.
bool pal::Motion::addGroupToGroup | ( | const std::string & | group, |
const std::string & | subgroup | ||
) |
Definition at line 522 of file motion_model.cpp.
void pal::Motion::addJointModel | ( | const std::string & | joint_name, |
const JointModel & | joint_model | ||
) |
Definition at line 389 of file motion_model.cpp.
void pal::Motion::addJointToGroup | ( | const std::string & | group, |
const std::string & | joint | ||
) |
Definition at line 514 of file motion_model.cpp.
void pal::Motion::addKeyFrame | ( | const sensor_msgs::JointStateConstPtr & | msg, |
float | time_increment = DEFAULT_TIME |
||
) |
Definition at line 353 of file motion_model.cpp.
double pal::Motion::changeJoint | ( | int | frame, |
const std::string & | joint_name, | ||
double | position | ||
) |
Definition at line 405 of file motion_model.cpp.
void pal::Motion::changeTime | ( | int | frame, |
float | time_increment | ||
) |
Definition at line 394 of file motion_model.cpp.
void pal::Motion::copyFrame | ( | int | frame, |
int | new_frame_pos = -1 |
||
) |
Definition at line 436 of file motion_model.cpp.
void pal::Motion::extendFrames | ( | const sensor_msgs::JointStateConstPtr & | msg | ) |
Definition at line 497 of file motion_model.cpp.
|
inline |
Definition at line 273 of file motion_model.h.
|
inline |
Definition at line 214 of file motion_model.h.
|
inline |
Definition at line 263 of file motion_model.h.
|
inline |
Definition at line 253 of file motion_model.h.
|
inline |
Definition at line 186 of file motion_model.h.
|
inline |
Definition at line 182 of file motion_model.h.
|
inline |
Definition at line 210 of file motion_model.h.
|
inline |
Definition at line 178 of file motion_model.h.
|
inline |
Definition at line 170 of file motion_model.h.
|
inline |
Definition at line 230 of file motion_model.h.
|
inline |
Definition at line 174 of file motion_model.h.
void pal::Motion::loadFrame | ( | int | frame | ) | const |
Definition at line 455 of file motion_model.cpp.
void pal::Motion::loadYAML | ( | double | downshift | ) | const |
Definition at line 476 of file motion_model.cpp.
PrintMotion pal::Motion::print | ( | double | downshift = 1.0 | ) | const |
Definition at line 541 of file motion_model.cpp.
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.
void pal::Motion::removeAllKeyFrames | ( | ) |
Definition at line 546 of file motion_model.cpp.
void pal::Motion::removeKeyFrame | ( | int | frame | ) |
Definition at line 431 of file motion_model.cpp.
|
inline |
Definition at line 218 of file motion_model.h.
|
inline |
Definition at line 241 of file motion_model.h.
void pal::Motion::setMotionGroups | ( | const std::string & | robot_description, |
const std::string & | robot_description_semantic | ||
) |
Definition at line 232 of file motion_model.cpp.
void pal::Motion::setParamName | ( | ) |
Definition at line 341 of file motion_model.cpp.
|
inline |
Definition at line 206 of file motion_model.h.
void pal::Motion::updateKeyFrame | ( | const sensor_msgs::JointStateConstPtr & | msg, |
int | frame | ||
) |
Definition at line 373 of file motion_model.cpp.
|
static |
Definition at line 141 of file motion_model.h.
|
private |
Definition at line 300 of file motion_model.h.
|
private |
Definition at line 301 of file motion_model.h.
|
private |
Definition at line 299 of file motion_model.h.
|
private |
Definition at line 302 of file motion_model.h.
|
private |
Definition at line 298 of file motion_model.h.
|
private |
Definition at line 297 of file motion_model.h.