39 #include <moveit_msgs/msg/display_robot_state.hpp>
81 return srdf_config_->getPlanningScene()->getCurrentStateNonConst();
100 std::vector<const moveit::core::JointModel*>
getSimpleJointModels(
const std::string& group_name)
const;
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setToCurrentValues(srdf::Model::GroupState &group_state)
std::vector< srdf::Model::GroupState > & getGroupStates()
moveit::core::RobotState & getState()
void loadAllowedCollisionMatrix()
Load the allowed collision matrix from the SRDF's list of link pairs.
std::vector< std::string > getGroupNames() const
std::vector< const moveit::core::JointModel * > getSimpleJointModels(const std::string &group_name) const
Returns a vector of joint models for the given group name.
void onInit() override
Overridable initialization method.
void publishState(const moveit::core::RobotState &robot_state)
Publish the given state on the moveit_robot_state topic.
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
srdf::Model::GroupState * findPoseByName(const std::string &name, const std::string &group)
collision_detection::CollisionRequest request_
bool isReady() const override
Return true if the data necessary to proceed with this step has been configured.
rclcpp::Publisher< moveit_msgs::msg::DisplayRobotState >::SharedPtr pub_robot_state_
Remember the publisher for quick publishing later.
bool checkSelfCollision(const moveit::core::RobotState &robot_state)
Check if the given robot state is in collision.
std::string getName() const override
Returns the name of the setup step.
void removePoseByName(const std::string &pose_name, const std::string &group_name)
Setup Step that contains the SRDFConfig.
std::shared_ptr< SRDFConfig > srdf_config_
Representation of a collision checking request.