moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <robot_poses.hpp>
Public Member Functions | |
std::string | getName () const override |
Returns the name of the setup step. More... | |
void | onInit () override |
Overridable initialization method. More... | |
bool | isReady () const override |
Return true if the data necessary to proceed with this step has been configured. More... | |
std::vector< std::string > | getGroupNames () const |
srdf::Model::GroupState * | findPoseByName (const std::string &name, const std::string &group) |
std::vector< srdf::Model::GroupState > & | getGroupStates () |
moveit::core::RobotState & | getState () |
void | publishState (const moveit::core::RobotState &robot_state) |
Publish the given state on the moveit_robot_state topic. More... | |
bool | checkSelfCollision (const moveit::core::RobotState &robot_state) |
Check if the given robot state is in collision. More... | |
std::vector< const moveit::core::JointModel * > | getSimpleJointModels (const std::string &group_name) const |
Returns a vector of joint models for the given group name. More... | |
void | removePoseByName (const std::string &pose_name, const std::string &group_name) |
void | setToCurrentValues (srdf::Model::GroupState &group_state) |
void | loadAllowedCollisionMatrix () |
Load the allowed collision matrix from the SRDF's list of link pairs. More... | |
Public Member Functions inherited from moveit_setup::srdf_setup::SRDFStep | |
void | onInit () override |
Overridable initialization method. More... | |
bool | isReady () const override |
Return true if the data necessary to proceed with this step has been configured. More... | |
bool | hasGroups () const |
Public Member Functions inherited from moveit_setup::SetupStep | |
SetupStep ()=default | |
SetupStep (const SetupStep &)=default | |
SetupStep (SetupStep &&)=default | |
SetupStep & | operator= (const SetupStep &)=default |
SetupStep & | operator= (SetupStep &&)=default |
virtual | ~SetupStep ()=default |
void | initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data) |
Called after construction to initialize the step. More... | |
const rclcpp::Logger & | getLogger () const |
Makes a namespaced logger for this step available to the widget. More... | |
Protected Attributes | |
rclcpp::Publisher< moveit_msgs::msg::DisplayRobotState >::SharedPtr | pub_robot_state_ |
Remember the publisher for quick publishing later. More... | |
collision_detection::CollisionRequest | request_ |
collision_detection::AllowedCollisionMatrix | allowed_collision_matrix_ |
Allowed collision matrix for robot poses. More... | |
Protected Attributes inherited from moveit_setup::srdf_setup::SRDFStep | |
std::shared_ptr< SRDFConfig > | srdf_config_ |
Protected Attributes inherited from moveit_setup::SetupStep | |
DataWarehousePtr | config_data_ |
rclcpp::Node::SharedPtr | parent_node_ |
std::shared_ptr< rclcpp::Logger > | logger_ |
Definition at line 46 of file robot_poses.hpp.
bool moveit_setup::srdf_setup::RobotPoses::checkSelfCollision | ( | const moveit::core::RobotState & | robot_state | ) |
Check if the given robot state is in collision.
Definition at line 111 of file robot_poses.cpp.
srdf::Model::GroupState * moveit_setup::srdf_setup::RobotPoses::findPoseByName | ( | const std::string & | name, |
const std::string & | group | ||
) |
Find the associated data by name
name | - name of data to find in datastructure |
Definition at line 66 of file robot_poses.cpp.
|
inline |
Definition at line 61 of file robot_poses.hpp.
|
inline |
Definition at line 74 of file robot_poses.hpp.
|
inlineoverridevirtual |
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 49 of file robot_poses.hpp.
std::vector< const moveit::core::JointModel * > moveit_setup::srdf_setup::RobotPoses::getSimpleJointModels | ( | const std::string & | group_name | ) | const |
Returns a vector of joint models for the given group name.
runtime_error | if the group does not exist |
Note: "Simple" means we exclude Passive/Mimic/MultiDOF joints
Definition at line 119 of file robot_poses.cpp.
|
inline |
Definition at line 79 of file robot_poses.hpp.
|
inlineoverridevirtual |
Return true if the data necessary to proceed with this step has been configured.
Reimplemented from moveit_setup::SetupStep.
Definition at line 56 of file robot_poses.hpp.
void moveit_setup::srdf_setup::RobotPoses::loadAllowedCollisionMatrix | ( | ) |
Load the allowed collision matrix from the SRDF's list of link pairs.
Definition at line 86 of file robot_poses.cpp.
|
overridevirtual |
Overridable initialization method.
Reimplemented from moveit_setup::SetupStep.
Definition at line 44 of file robot_poses.cpp.
void moveit_setup::srdf_setup::RobotPoses::publishState | ( | const moveit::core::RobotState & | robot_state | ) |
Publish the given state on the moveit_robot_state topic.
Definition at line 101 of file robot_poses.cpp.
|
inline |
Definition at line 102 of file robot_poses.hpp.
void moveit_setup::srdf_setup::RobotPoses::setToCurrentValues | ( | srdf::Model::GroupState & | group_state | ) |
|
protected |
Allowed collision matrix for robot poses.
Definition at line 122 of file robot_poses.hpp.
|
protected |
Remember the publisher for quick publishing later.
Definition at line 114 of file robot_poses.hpp.
|
protected |
Definition at line 119 of file robot_poses.hpp.