collision_check.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : collision_check.h
3  * Project : moveit_servo
4  * Created : 1/11/2019
5  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
6  *
7  * BSD 3-Clause License
8  *
9  * Copyright (c) 2019, Los Alamos National Security, LLC
10  * All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions are met:
14  *
15  * * Redistributions of source code must retain the above copyright notice, this
16  * list of conditions and the following disclaimer.
17  *
18  * * Redistributions in binary form must reproduce the above copyright notice,
19  * this list of conditions and the following disclaimer in the documentation
20  * and/or other materials provided with the distribution.
21  *
22  * * Neither the name of the copyright holder nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE
30  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
31  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
32  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
33  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
34  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
35  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
36  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *******************************************************************************/
38 
39 #pragma once
40 
41 #include <moveit/collision_detection/collision_common.h>
44 #include <sensor_msgs/JointState.h>
45 #include <std_msgs/Float64.h>
46 
49 
50 namespace moveit_servo
51 {
53 {
55  K_STOP_DISTANCE = 2
56 };
57 
58 class CollisionCheck
59 {
60 public:
67  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
68 
70  {
71  timer_.stop();
72  }
73 
75  void start();
76 
78  void setPaused(bool paused);
79 
80 private:
82  void run(const ros::TimerEvent& timer_event);
83 
86 
88  void worstCaseStopTimeCB(const std_msgs::Float64ConstPtr& msg);
89 
91 
92  // Parameters from yaml
94 
95  // Pointer to the collision environment
96  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
97 
98  // RobotState buffer used for collision checking
99  robot_state::RobotStatePtr current_state_;
100 
101  // Scale robot velocity according to collision proximity and user-defined thresholds.
102  // I scaled exponentially (cubic power) so velocity drops off quickly after the threshold.
103  // Proximity decreasing --> decelerate
105  double velocity_scale_ = 1;
106  double self_collision_distance_ = 0;
107  double scene_collision_distance_ = 0;
108  bool collision_detected_ = false;
109  bool paused_ = false;
110 
111  // Variables for stop-distance-based collision checking
112  double current_collision_distance_ = 0;
114  double prev_collision_distance_ = 0;
115  double est_time_to_collision_ = 0;
116  double safety_factor_ = 1000;
117  double worst_case_stop_time_ = std::numeric_limits<double>::max();
118 
121 
122  // collision request
125 
126  // ROS
132 };
133 } // namespace moveit_servo
planning_scene_monitor
moveit_servo::CollisionCheck::parameters_
const ServoParameters & parameters_
Definition: collision_check.h:129
moveit_servo::K_STOP_DISTANCE
@ K_STOP_DISTANCE
Definition: collision_check.h:127
moveit_servo::CollisionCheck
Definition: collision_check.h:94
ros::Publisher
moveit_servo::CollisionCheck::setPaused
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
Definition: collision_check.cpp:208
ros::Timer::stop
void stop()
moveit_servo::CollisionCheck::current_state_
robot_state::RobotStatePtr current_state_
Definition: collision_check.h:135
moveit_servo::CollisionCheck::start
void start()
start the Timer that regulates collision check rate
Definition: collision_check.cpp:90
moveit_servo::CollisionCheck::self_velocity_scale_coefficient_
const double self_velocity_scale_coefficient_
Definition: collision_check.h:155
moveit_servo::CollisionCheck::~CollisionCheck
~CollisionCheck()
Definition: collision_check.h:105
robot_model_loader.h
moveit_servo::CollisionCheck::scene_velocity_scale_coefficient_
const double scene_velocity_scale_coefficient_
Definition: collision_check.h:156
moveit_servo::CollisionCheck::nh_
ros::NodeHandle nh_
Definition: collision_check.h:126
moveit_servo::CollisionCheck::prev_collision_distance_
double prev_collision_distance_
Definition: collision_check.h:150
moveit_servo::CollisionCheck::current_collision_distance_
double current_collision_distance_
Definition: collision_check.h:148
collision_detection::CollisionRequest
moveit_servo::CollisionCheck::CollisionCheck
CollisionCheck(ros::NodeHandle &nh, const moveit_servo::ServoParameters &parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor.
Definition: collision_check.cpp:53
moveit_servo::CollisionCheck::collision_detected_
bool collision_detected_
Definition: collision_check.h:144
moveit_servo::CollisionCheck::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: collision_check.h:132
moveit_servo::CollisionCheckType
CollisionCheckType
Definition: collision_check.h:88
moveit_servo::ServoParameters
Definition: servo_parameters.h:83
moveit_servo::K_THRESHOLD_DISTANCE
@ K_THRESHOLD_DISTANCE
Definition: collision_check.h:126
collision_detection::CollisionResult
planning_scene_monitor.h
moveit_servo::CollisionCheck::collision_result_
collision_detection::CollisionResult collision_result_
Definition: collision_check.h:160
moveit_servo
Definition: collision_check.h:50
moveit_servo::CollisionCheck::velocity_scale_
double velocity_scale_
Definition: collision_check.h:141
moveit_servo::CollisionCheck::collision_request_
collision_detection::CollisionRequest collision_request_
Definition: collision_check.h:159
moveit_servo::CollisionCheck::worst_case_stop_time_sub_
ros::Subscriber worst_case_stop_time_sub_
Definition: collision_check.h:167
moveit_servo::CollisionCheck::run
void run(const ros::TimerEvent &timer_event)
Run one iteration of collision checking.
Definition: collision_check.cpp:95
ros::TimerEvent
moveit_servo::CollisionCheck::est_time_to_collision_
double est_time_to_collision_
Definition: collision_check.h:151
moveit_servo::CollisionCheck::safety_factor_
double safety_factor_
Definition: collision_check.h:152
moveit_servo::CollisionCheck::joint_state_sub_
ros::Subscriber joint_state_sub_
Definition: collision_check.h:165
moveit_servo::CollisionCheck::worst_case_stop_time_
double worst_case_stop_time_
Definition: collision_check.h:153
moveit_servo::CollisionCheck::scene_collision_distance_
double scene_collision_distance_
Definition: collision_check.h:143
moveit_servo::CollisionCheck::worstCaseStopTimeCB
void worstCaseStopTimeCB(const std_msgs::Float64ConstPtr &msg)
Callback for stopping time, from the thread that is aware of velocity and acceleration.
Definition: collision_check.cpp:203
planning_scene_monitor::LockedPlanningSceneRO
moveit_servo::CollisionCheck::paused_
bool paused_
Definition: collision_check.h:145
moveit_servo::CollisionCheck::collision_check_type_
CollisionCheckType collision_check_type_
Definition: collision_check.h:140
moveit_servo::CollisionCheck::self_collision_distance_
double self_collision_distance_
Definition: collision_check.h:142
servo_parameters.h
moveit_servo::CollisionCheck::getLockedPlanningSceneRO
planning_scene_monitor::LockedPlanningSceneRO getLockedPlanningSceneRO() const
Get a read-only copy of the planning scene.
Definition: collision_check.cpp:85
moveit_servo::CollisionCheck::collision_velocity_scale_pub_
ros::Publisher collision_velocity_scale_pub_
Definition: collision_check.h:166
ros::Duration
ros::Timer
moveit_servo::CollisionCheck::derivative_of_collision_distance_
double derivative_of_collision_distance_
Definition: collision_check.h:149
moveit_servo::CollisionCheck::timer_
ros::Timer timer_
Definition: collision_check.h:163
ros::NodeHandle
ros::Subscriber
moveit_servo::CollisionCheck::period_
ros::Duration period_
Definition: collision_check.h:164
low_pass_filter.h


moveit_servo
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56