moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_check.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, LLC
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Title : collision_check.cpp
35  * Project : moveit_servo
36  * Created : 1/11/2019
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
38  */
39 
40 #include <std_msgs/msg/float64.hpp>
41 
43 // #include <moveit_servo/make_shared_from_pool.h>
44 
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.collision_check");
46 static const double MIN_RECOMMENDED_COLLISION_RATE = 10;
47 constexpr size_t ROS_LOG_THROTTLE_PERIOD = 30 * 1000; // Milliseconds to throttle logs inside loops
48 
49 namespace moveit_servo
50 {
51 // Constructor for the class that handles collision checking
52 CollisionCheck::CollisionCheck(const rclcpp::Node::SharedPtr& node, const ServoParameters::SharedConstPtr& parameters,
53  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor)
54  : node_(node)
55  , parameters_(parameters)
56  , planning_scene_monitor_(planning_scene_monitor)
57  , self_velocity_scale_coefficient_(-log(0.001) / parameters->self_collision_proximity_threshold)
58  , scene_velocity_scale_coefficient_(-log(0.001) / parameters->scene_collision_proximity_threshold)
59  , period_(1. / parameters->collision_check_rate)
60 {
61  // Init collision request
62  collision_request_.group_name = parameters_->move_group_name;
63  collision_request_.distance = true; // enable distance-based collision checking
64  collision_request_.contacts = true; // Record the names of collision pairs
65 
66  if (parameters_->collision_check_rate < MIN_RECOMMENDED_COLLISION_RATE)
67  {
68  auto& clk = *node_->get_clock();
69  RCLCPP_WARN_STREAM_THROTTLE(LOGGER, clk, ROS_LOG_THROTTLE_PERIOD,
70  "Collision check rate is low, increase it in yaml file if CPU allows");
71  }
72 
73  // ROS pubs/subs
74  collision_velocity_scale_pub_ =
75  node_->create_publisher<std_msgs::msg::Float64>("~/collision_velocity_scale", rclcpp::SystemDefaultsQoS());
76 
77  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
78 }
79 
81 {
82  timer_ = node_->create_wall_timer(std::chrono::duration<double>(period_), [this]() { return run(); });
83 }
84 
85 void CollisionCheck::run()
86 {
87  if (paused_)
88  {
89  return;
90  }
91 
92  // Update to the latest current state
93  current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
94  current_state_->updateCollisionBodyTransforms();
95  collision_detected_ = false;
96 
97  // Do a timer-safe distance-based collision detection
98  collision_result_.clear();
99  auto locked_scene = planning_scene_monitor::LockedPlanningSceneRO(planning_scene_monitor_);
100  locked_scene->getCollisionEnv()->checkRobotCollision(collision_request_, collision_result_, *current_state_,
101  locked_scene->getAllowedCollisionMatrix());
102  scene_collision_distance_ = collision_result_.distance;
103  collision_detected_ |= collision_result_.collision;
104  collision_result_.print();
105 
106  collision_result_.clear();
107  // Self-collisions and scene collisions are checked separately so different thresholds can be used
108  locked_scene->getCollisionEnvUnpadded()->checkSelfCollision(collision_request_, collision_result_, *current_state_,
109  locked_scene->getAllowedCollisionMatrix());
110  self_collision_distance_ = collision_result_.distance;
111  collision_detected_ |= collision_result_.collision;
112  collision_result_.print();
113 
114  velocity_scale_ = 1;
115  // If we're definitely in collision, stop immediately
116  if (collision_detected_)
117  {
118  velocity_scale_ = 0;
119  }
120  else
121  {
122  // If we are far from a collision, velocity_scale should be 1.
123  // If we are very close to a collision, velocity_scale should be ~zero.
124  // When scene_collision_proximity_threshold is breached, start decelerating exponentially.
125  if (scene_collision_distance_ < parameters_->scene_collision_proximity_threshold)
126  {
127  // velocity_scale = e ^ k * (collision_distance - threshold)
128  // k = - ln(0.001) / collision_proximity_threshold
129  // velocity_scale should equal one when collision_distance is at collision_proximity_threshold.
130  // velocity_scale should equal 0.001 when collision_distance is at zero.
131  velocity_scale_ = std::min(velocity_scale_,
132  exp(scene_velocity_scale_coefficient_ *
133  (scene_collision_distance_ - parameters_->scene_collision_proximity_threshold)));
134  }
135 
136  if (self_collision_distance_ < parameters_->self_collision_proximity_threshold)
137  {
138  velocity_scale_ =
139  std::min(velocity_scale_, exp(self_velocity_scale_coefficient_ *
140  (self_collision_distance_ - parameters_->self_collision_proximity_threshold)));
141  }
142  }
143 
144  // publish message
145  {
146  auto msg = std::make_unique<std_msgs::msg::Float64>();
147  msg->data = velocity_scale_;
148  collision_velocity_scale_pub_->publish(std::move(msg));
149  }
150 }
151 
152 void CollisionCheck::setPaused(bool paused)
153 {
154  paused_ = paused;
155 }
156 
157 } // namespace moveit_servo
CollisionCheck(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor.
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
void start()
start the Timer that regulates collision check rate
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
constexpr size_t ROS_LOG_THROTTLE_PERIOD
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool distance
If true, compute proximity distance.
void print() const
Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level...
double distance
Closest distance between two bodies.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
std::shared_ptr< const ServoParameters > SharedConstPtr