moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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 <default_response_adapter_parameters.hpp>
47{
53{
54public:
55 ValidateSolution() : logger_(moveit::getLogger("moveit.ros.validate_solution"))
56 {
57 }
58
59 void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
60 {
61 auto param_listener =
62 std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
63 // Read parameters
64 const auto params = param_listener->get_params();
65
66 if (!params.display_contacts_topic.empty())
67 {
68 contacts_publisher_ = node->create_publisher<visualization_msgs::msg::MarkerArray>(params.display_contacts_topic,
69 rclcpp::SystemDefaultsQoS());
70 }
71 }
72
73 [[nodiscard]] std::string getDescription() const override
74 {
75 return std::string("ValidateSolution");
76 }
77
78 void adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
81 {
82 RCLCPP_DEBUG(logger_, " Running '%s'", getDescription().c_str());
83 if (!res.trajectory)
84 {
85 RCLCPP_ERROR(logger_, "No motion path to display in MotionPlanResponse.");
86 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
87 return;
88 }
89
90 std::size_t state_count = res.trajectory->getWayPointCount();
91 RCLCPP_DEBUG(logger_, "Motion planner reported a solution path with %ld states", state_count);
92 visualization_msgs::msg::MarkerArray arr;
93 visualization_msgs::msg::Marker m;
94 m.action = visualization_msgs::msg::Marker::DELETEALL;
95 arr.markers.push_back(m);
96
97 std::vector<std::size_t> indices;
98 if (!planning_scene->isPathValid(*res.trajectory, req.path_constraints, req.group_name, false, &indices))
99 {
100 // check to see if there is any problem with the states that are found to be invalid
101 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
102
103 // If a contact publisher exists, publish contacts
104 if (contacts_publisher_)
105 {
106 // display error messages
107 std::stringstream ss;
108 for (std::size_t it : indices)
109 {
110 ss << it << ' ';
111 }
112
113 RCLCPP_ERROR_STREAM(logger_, "Computed path is not valid. Invalid states at index locations: [ "
114 << ss.str() << "] out of " << state_count
115 << ". Explanations follow in command line. Contacts are published on "
116 << contacts_publisher_->get_topic_name());
117
118 // call validity checks in verbose mode for the problematic states
119 for (std::size_t it : indices)
120 {
121 // check validity with verbose on
122 const moveit::core::RobotState& robot_state = res.trajectory->getWayPoint(it);
123 planning_scene->isStateValid(robot_state, req.path_constraints, req.group_name, true);
124
125 // compute the contacts if any
128 c_req.contacts = true;
129 c_req.max_contacts = 10;
130 c_req.max_contacts_per_pair = 3;
131 c_req.verbose = false;
132 planning_scene->checkCollision(c_req, c_res, robot_state);
133 if (c_res.contact_count > 0)
134 {
135 visualization_msgs::msg::MarkerArray arr_i;
137 c_res.contacts);
138 arr.markers.insert(arr.markers.end(), arr_i.markers.begin(), arr_i.markers.end());
139 }
140 }
141 RCLCPP_ERROR(logger_, "Completed listing of explanations for invalid states.");
142 contacts_publisher_->publish(arr);
143 }
144 }
145 }
146
147private:
148 rclcpp::Logger logger_;
149 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr contacts_publisher_;
150};
151} // namespace default_planning_response_adapters
152
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.
Definition robot_state.h:90
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.
Definition exceptions.h:43
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