Class Motion
Defined in File motion_model.hpp
Class Documentation
-
class Motion
The Motion class represents a complex motion of the robot, encoded as a sequence of Keyframes at specific times
Public Functions
-
Motion(const rclcpp::Logger &logger, const std::string &robot_description, const std::string &robot_description_semantic, const std::vector<std::string> &extra_joints)
-
Motion(const rclcpp::Logger &logger, const play_motion2_msgs::msg::Motion &motion_cfg, const std::string &robot_description, const std::string &robot_description_semantic, const std::vector<std::string> &extra_joints)
-
void setMotionGroups(const std::string &robot_description, const std::string &robot_description_semantic)
-
void setParamName()
-
void addKeyFrame(const sensor_msgs::msg::JointState &msg, float time_increment = DEFAULT_TIME)
-
void updateKeyFrame(const sensor_msgs::msg::JointState &msg, int frame)
-
void addJointModel(const std::string &joint_name, const JointModel &joint_model)
-
void changeTime(int frame, float time_increment)
-
double changeJoint(int frame, const std::string &joint_name, double position)
-
void removeKeyFrame(int frame)
-
void copyFrame(int frame, int new_frame_pos = -1)
-
void loadFrame(int frame) const
-
void loadYAML(double downshift) const
-
void extendFrames(const sensor_msgs::msg::JointState &msg)
-
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 addJointToGroup(const std::string &group, const std::string &joint)
-
bool addGroupToGroup(const std::string &group, const std::string &subgroup)
-
inline const std::string &getParamName() const
-
inline bool jointsLoaded()
-
inline std::vector<std::string> getJoints() const
-
inline std::size_t size() const
-
inline const std::string &getCurrentGroup()
-
inline void addJointPositionToNanJointKeyframes(const sensor_msgs::msg::JointState &joint_state_msg, const std::string &joint_name)
-
inline bool setCurrentGroup(const std::string &group, const sensor_msgs::msg::JointState &joint_state_msg)
-
inline bool isJointUsed(const std::string &joint_name) const
-
inline bool setExtraJointUsedState(const std::string &name, bool used, const sensor_msgs::msg::JointState &joint_state_msg = sensor_msgs::msg::JointState())
-
inline std::vector<std::string> getJointGroups()
-
inline std::vector<std::string> getExtraJoints()
-
inline std::vector<std::string> getAvailableJoints()
Public Static Attributes
-
static const float DEFAULT_TIME
-
Motion(const rclcpp::Logger &logger, const std::string &robot_description, const std::string &robot_description_semantic, const std::vector<std::string> &extra_joints)