40 #include <std_msgs/msg/float64.hpp>
45 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_servo.collision_check");
46 static const double MIN_RECOMMENDED_COLLISION_RATE = 10;
55 , parameters_(parameters)
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)
62 collision_request_.
group_name = parameters_->move_group_name;
66 if (parameters_->collision_check_rate < MIN_RECOMMENDED_COLLISION_RATE)
68 auto& clk = *node_->get_clock();
70 "Collision check rate is low, increase it in yaml file if CPU allows");
74 collision_velocity_scale_pub_ =
75 node_->create_publisher<std_msgs::msg::Float64>(
"~/collision_velocity_scale", rclcpp::SystemDefaultsQoS());
77 current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
82 timer_ = node_->create_wall_timer(std::chrono::duration<double>(period_), [
this]() {
return run(); });
85 void CollisionCheck::run()
93 current_state_ = planning_scene_monitor_->getStateMonitor()->getCurrentState();
94 current_state_->updateCollisionBodyTransforms();
95 collision_detected_ =
false;
98 collision_result_.
clear();
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();
106 collision_result_.
clear();
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();
116 if (collision_detected_)
125 if (scene_collision_distance_ < parameters_->scene_collision_proximity_threshold)
131 velocity_scale_ = std::min(velocity_scale_,
132 exp(scene_velocity_scale_coefficient_ *
133 (scene_collision_distance_ - parameters_->scene_collision_proximity_threshold)));
136 if (self_collision_distance_ < parameters_->self_collision_proximity_threshold)
139 std::min(velocity_scale_, exp(self_velocity_scale_coefficient_ *
140 (self_collision_distance_ - parameters_->self_collision_proximity_threshold)));
146 auto msg = std::make_unique<std_msgs::msg::Float64>();
147 msg->data = velocity_scale_;
148 collision_velocity_scale_pub_->publish(std::move(msg));
CollisionCheck(const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr ¶meters, 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
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