moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
check_start_state_collision.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, 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 Willow Garage 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: This adapter checks if the start state is in collision.
37 */
38
42#include <class_loader/class_loader.hpp>
43#include <rclcpp/logging.hpp>
44#include <rclcpp/node.hpp>
45#include <rclcpp/parameter_value.hpp>
47
48#include <default_request_adapter_parameters.hpp>
49
51{
52
55{
56public:
57 CheckStartStateCollision() : logger_(moveit::getLogger("moveit.ros.validate_start_state"))
58 {
59 }
60
61 [[nodiscard]] std::string getDescription() const override
62 {
63 return std::string("CheckStartStateCollision");
64 }
65
66 [[nodiscard]] moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
67 planning_interface::MotionPlanRequest& req) const override
68 {
69 RCLCPP_DEBUG(logger_, "Running '%s'", getDescription().c_str());
70
71 // Get the start state TODO(sjahr): Should we check if req.start state == planning scene start state?
72 moveit::core::RobotState start_state = planning_scene->getCurrentState();
73 moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
74
76 creq.group_name = req.group_name;
78 // TODO(sjahr): Would verbose make sense?
79 planning_scene->checkCollision(creq, cres, start_state);
80
81 auto status = moveit::core::MoveItErrorCode();
82 if (!cres.collision)
83 {
84 status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
85 }
86 else
87 {
89 planning_scene->getCollidingPairs(contacts);
90
91 std::string contact_information = std::to_string(contacts.size()) + " contact(s) detected : ";
92
93 for (const auto& [contact_pair, contact_info] : contacts)
94 {
95 contact_information.append(contact_pair.first + " - " + contact_pair.second + ", ");
96 }
97
98 status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_IN_COLLISION;
99 status.message = std::string(contact_information);
100 }
101 status.source = getDescription();
102 return status;
103 }
104
105private:
106 rclcpp::Logger logger_;
107};
108} // namespace default_planning_request_adapters
109
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.
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.
Definition robot_state.h:90
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.
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.
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.