40#include <class_loader/class_loader.hpp>
42#include <visualization_msgs/msg/marker_array.hpp>
45#include <moveit_ros_planning/default_response_adapter_parameters.hpp>
62 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
65 std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
67 const auto params = param_listener->get_params();
69 if (!params.display_contacts_topic.empty())
71 contacts_publisher_ = node->create_publisher<visualization_msgs::msg::MarkerArray>(params.display_contacts_topic,
72 rclcpp::SystemDefaultsQoS());
62 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override {
…}
78 return std::string(
"ValidateSolution");
88 RCLCPP_ERROR(logger_,
"No motion path to display in MotionPlanResponse.");
89 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
93 std::size_t state_count = res.
trajectory->getWayPointCount();
94 RCLCPP_DEBUG(logger_,
"Motion planner reported a solution path with %ld states", state_count);
95 visualization_msgs::msg::MarkerArray arr;
96 visualization_msgs::msg::Marker m;
97 m.action = visualization_msgs::msg::Marker::DELETEALL;
98 arr.markers.push_back(m);
100 std::vector<std::size_t> indices;
104 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
107 if (contacts_publisher_)
110 std::stringstream ss;
111 for (std::size_t it : indices)
116 RCLCPP_ERROR_STREAM(logger_,
"Computed path is not valid. Invalid states at index locations: [ "
117 << ss.str() <<
"] out of " << state_count
118 <<
". Explanations follow in command line. Contacts are published on "
119 << contacts_publisher_->get_topic_name());
122 for (std::size_t it : indices)
126 planning_scene->isStateValid(robot_state, req.path_constraints, req.group_name,
true);
138 visualization_msgs::msg::MarkerArray arr_i;
141 arr.markers.insert(arr.markers.end(), arr_i.markers.begin(), arr_i.markers.end());
144 RCLCPP_ERROR(logger_,
"Completed listing of explanations for invalid states.");
145 contacts_publisher_->publish(arr);
151 rclcpp::Logger logger_;
152 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr contacts_publisher_;
Adapter to check the request path validity (collision avoidance, feasibility and constraint satisfact...
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
void adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning response.
~ValidateSolution() override=default
std::string getDescription() const override
Get a description of this adapter.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning p...
void getCollisionMarkersFromContacts(visualization_msgs::msg::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::msg::ColorRGBA &color, const rclcpp::Duration &lifetime, const double radius=0.035)
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.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
Representation of a collision checking result.
std::size_t contact_count
Number of contacts returned.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory