moveit2
The MoveIt Motion Planning Framework for ROS 2.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Pages
validate_path.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, PickNik Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan, Sebastian Jahr
36 Desc: Response adapter that checks a path for validity (collision avoidance, feasibility and constraint satisfaction)
37*/
38
40#include <class_loader/class_loader.hpp>
42#include <visualization_msgs/msg/marker_array.hpp>
44
45#include <moveit_ros_planning/default_response_adapter_parameters.hpp>
46
48{
54{
55public:
56 ValidateSolution() : logger_(moveit::getLogger("moveit.ros.validate_solution"))
57 {
58 }
59
60 ~ValidateSolution() override = default;
61
62 void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
63 {
64 auto param_listener =
65 std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
66 // Read parameters
67 const auto params = param_listener->get_params();
68
69 if (!params.display_contacts_topic.empty())
70 {
71 contacts_publisher_ = node->create_publisher<visualization_msgs::msg::MarkerArray>(params.display_contacts_topic,
72 rclcpp::SystemDefaultsQoS());
73 }
74 }
75
76 [[nodiscard]] std::string getDescription() const override
77 {
78 return std::string("ValidateSolution");
79 }
80
81 void adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
84 {
85 RCLCPP_DEBUG(logger_, " Running '%s'", getDescription().c_str());
86 if (!res.trajectory)
87 {
88 RCLCPP_ERROR(logger_, "No motion path to display in MotionPlanResponse.");
89 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
90 return;
91 }
92
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);
99
100 std::vector<std::size_t> indices;
101 if (!planning_scene->isPathValid(*res.trajectory, req.path_constraints, req.group_name, false, &indices))
102 {
103 // check to see if there is any problem with the states that are found to be invalid
104 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
105
106 // If a contact publisher exists, publish contacts
107 if (contacts_publisher_)
108 {
109 // display error messages
110 std::stringstream ss;
111 for (std::size_t it : indices)
112 {
113 ss << it << ' ';
114 }
115
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());
120
121 // call validity checks in verbose mode for the problematic states
122 for (std::size_t it : indices)
123 {
124 // check validity with verbose on
125 const moveit::core::RobotState& robot_state = res.trajectory->getWayPoint(it);
126 planning_scene->isStateValid(robot_state, req.path_constraints, req.group_name, true);
127
128 // compute the contacts if any
131 c_req.contacts = true;
132 c_req.max_contacts = 10;
133 c_req.max_contacts_per_pair = 3;
134 c_req.verbose = false;
135 planning_scene->checkCollision(c_req, c_res, robot_state);
136 if (c_res.contact_count > 0)
137 {
138 visualization_msgs::msg::MarkerArray arr_i;
140 c_res.contacts);
141 arr.markers.insert(arr.markers.end(), arr_i.markers.begin(), arr_i.markers.end());
142 }
143 }
144 RCLCPP_ERROR(logger_, "Completed listing of explanations for invalid states.");
145 contacts_publisher_->publish(arr);
146 }
147 }
148 }
149
150private:
151 rclcpp::Logger logger_;
152 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr contacts_publisher_;
153};
154} // namespace default_planning_response_adapters
155
Adapter to check the request path validity (collision avoidance, feasibility and constraint satisfact...
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_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.
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.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory