moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Functions | |
void | update (moveit::core::RobotState *self, bool force, std::string &category) |
Eigen::MatrixXd | getFrameTransform (const moveit::core::RobotState *self, std::string &frame_id) |
Eigen::MatrixXd | getGlobalLinkTransform (const moveit::core::RobotState *self, std::string &link_name) |
geometry_msgs::msg::Pose | getPose (const moveit::core::RobotState *self, const std::string &link_name) |
std::map< std::string, double > | getJointPositions (const moveit::core::RobotState *self) |
void | setJointPositions (moveit::core::RobotState *self, std::map< std::string, double > &joint_positions) |
std::map< std::string, double > | getJointVelocities (const moveit::core::RobotState *self) |
void | setJointVelocities (moveit::core::RobotState *self, std::map< std::string, double > &joint_velocities) |
std::map< std::string, double > | getJointAccelerations (const moveit::core::RobotState *self) |
void | setJointAccelerations (moveit::core::RobotState *self, std::map< std::string, double > &joint_accelerations) |
std::map< std::string, double > | getJointEfforts (const moveit::core::RobotState *self) |
void | setJointEfforts (moveit::core::RobotState *self, std::map< std::string, double > &joint_efforts) |
Eigen::VectorXd | copyJointGroupPositions (const moveit::core::RobotState *self, const std::string &joint_model_group_name) |
Eigen::VectorXd | copyJointGroupVelocities (const moveit::core::RobotState *self, const std::string &joint_model_group_name) |
Eigen::VectorXd | copyJointGroupAccelerations (const moveit::core::RobotState *self, const std::string &joint_model_group_name) |
Eigen::MatrixXd | getJacobian (const moveit::core::RobotState *self, const std::string &joint_model_group_name, const Eigen::Vector3d &reference_point_position) |
Eigen::MatrixXd | getJacobian (const moveit::core::RobotState *self, const std::string &joint_model_group_name, const std::string &link_model_name, const Eigen::Vector3d &reference_point_position, bool use_quaternion_representation) |
bool | setToDefaultValues (moveit::core::RobotState *self, const std::string &joint_model_group_name, const std::string &state_name) |
void | initRobotState (py::module &m) |
Eigen::VectorXd moveit_py::bind_robot_state::copyJointGroupAccelerations | ( | const moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name | ||
) |
Definition at line 175 of file robot_state.cpp.
Eigen::VectorXd moveit_py::bind_robot_state::copyJointGroupPositions | ( | const moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name | ||
) |
Definition at line 161 of file robot_state.cpp.
Eigen::VectorXd moveit_py::bind_robot_state::copyJointGroupVelocities | ( | const moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name | ||
) |
Definition at line 168 of file robot_state.cpp.
Eigen::MatrixXd moveit_py::bind_robot_state::getFrameTransform | ( | const moveit::core::RobotState * | self, |
std::string & | frame_id | ||
) |
Definition at line 67 of file robot_state.cpp.
Eigen::MatrixXd moveit_py::bind_robot_state::getGlobalLinkTransform | ( | const moveit::core::RobotState * | self, |
std::string & | link_name | ||
) |
Definition at line 74 of file robot_state.cpp.
Eigen::MatrixXd moveit_py::bind_robot_state::getJacobian | ( | const moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name, | ||
const Eigen::Vector3d & | reference_point_position | ||
) |
Definition at line 183 of file robot_state.cpp.
Eigen::MatrixXd moveit_py::bind_robot_state::getJacobian | ( | const moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name, | ||
const std::string & | link_model_name, | ||
const Eigen::Vector3d & | reference_point_position, | ||
bool | use_quaternion_representation | ||
) |
std::map< std::string, double > moveit_py::bind_robot_state::getJointAccelerations | ( | const moveit::core::RobotState * | self | ) |
Definition at line 123 of file robot_state.cpp.
std::map< std::string, double > moveit_py::bind_robot_state::getJointEfforts | ( | const moveit::core::RobotState * | self | ) |
Definition at line 142 of file robot_state.cpp.
std::map< std::string, double > moveit_py::bind_robot_state::getJointPositions | ( | const moveit::core::RobotState * | self | ) |
Definition at line 85 of file robot_state.cpp.
std::map< std::string, double > moveit_py::bind_robot_state::getJointVelocities | ( | const moveit::core::RobotState * | self | ) |
Definition at line 104 of file robot_state.cpp.
geometry_msgs::msg::Pose moveit_py::bind_robot_state::getPose | ( | const moveit::core::RobotState * | self, |
const std::string & | link_name | ||
) |
Definition at line 80 of file robot_state.cpp.
void moveit_py::bind_robot_state::initRobotState | ( | py::module & | m | ) |
Definition at line 209 of file robot_state.cpp.
void moveit_py::bind_robot_state::setJointAccelerations | ( | moveit::core::RobotState * | self, |
std::map< std::string, double > & | joint_accelerations | ||
) |
Definition at line 134 of file robot_state.cpp.
void moveit_py::bind_robot_state::setJointEfforts | ( | moveit::core::RobotState * | self, |
std::map< std::string, double > & | joint_efforts | ||
) |
Definition at line 153 of file robot_state.cpp.
void moveit_py::bind_robot_state::setJointPositions | ( | moveit::core::RobotState * | self, |
std::map< std::string, double > & | joint_positions | ||
) |
Definition at line 96 of file robot_state.cpp.
void moveit_py::bind_robot_state::setJointVelocities | ( | moveit::core::RobotState * | self, |
std::map< std::string, double > & | joint_velocities | ||
) |
Definition at line 115 of file robot_state.cpp.
bool moveit_py::bind_robot_state::setToDefaultValues | ( | moveit::core::RobotState * | self, |
const std::string & | joint_model_group_name, | ||
const std::string & | state_name | ||
) |
Definition at line 201 of file robot_state.cpp.
void moveit_py::bind_robot_state::update | ( | moveit::core::RobotState * | self, |
bool | force, | ||
std::string & | category | ||
) |
Definition at line 47 of file robot_state.cpp.