42#include <class_loader/class_loader.hpp>
43#include <rclcpp/logging.hpp>
44#include <rclcpp/node.hpp>
45#include <rclcpp/parameter_value.hpp>
48#include <default_request_adapter_parameters.hpp>
63 return std::string(
"CheckStartStateCollision");
84 status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
91 std::string contact_information = std::to_string(contacts.size()) +
" contact(s) detected : ";
93 for (
const auto& [contact_pair, contact_info] : contacts)
95 contact_information.append(contact_pair.first +
" - " + contact_pair.second +
", ");
98 status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_IN_COLLISION;
99 status.message = std::string(contact_information);
106 rclcpp::Logger logger_;
This adapter checks if the start state is in collision.
std::string getDescription() const override
Get a description of this adapter.
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
CheckStartStateCollision()
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
Representation of a collision checking result.
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.
bool collision
True if collision was found, false otherwise.