Class RobotPoses
Defined in File robot_poses.hpp
Inheritance Relationships
Base Type
public moveit_setup::srdf_setup::SRDFStep
(Class SRDFStep)
Class Documentation
-
class RobotPoses : public moveit_setup::srdf_setup::SRDFStep
Public Functions
-
inline virtual std::string getName() const override
-
virtual void onInit() override
-
inline virtual bool isReady() const override
-
inline std::vector<std::string> getGroupNames() const
-
srdf::Model::GroupState *findPoseByName(const std::string &name, const std::string &group)
Find the associated data by name
- Parameters:
name – - name of data to find in datastructure
- Returns:
pointer to data in datastructure
-
inline std::vector<srdf::Model::GroupState> &getGroupStates()
-
inline moveit::core::RobotState &getState()
-
void publishState(const moveit::core::RobotState &robot_state)
Publish the given state on the moveit_robot_state topic.
-
bool checkSelfCollision(const moveit::core::RobotState &robot_state)
Check if the given robot state is in collision.
-
std::vector<const moveit::core::JointModel*> getSimpleJointModels(const std::string &group_name) const
Returns a vector of joint models for the given group name.
Note: “Simple” means we exclude Passive/Mimic/MultiDOF joints
- Throws:
runtime_error – if the group does not exist
-
inline 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.
Protected Attributes
-
rclcpp::Publisher<moveit_msgs::msg::DisplayRobotState>::SharedPtr pub_robot_state_
Remember the publisher for quick publishing later.
-
collision_detection::CollisionRequest request_
-
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
-
inline virtual std::string getName() const override