#include <collision_check.h>
Definition at line 94 of file collision_check.h.
◆ CollisionCheck()
◆ ~CollisionCheck()
moveit_servo::CollisionCheck::~CollisionCheck |
( |
| ) |
|
|
inline |
◆ getLockedPlanningSceneRO()
◆ run()
void moveit_servo::CollisionCheck::run |
( |
const ros::TimerEvent & |
timer_event | ) |
|
|
private |
◆ setPaused()
void moveit_servo::CollisionCheck::setPaused |
( |
bool |
paused | ) |
|
Pause or unpause processing servo commands while keeping the timers alive.
Definition at line 208 of file collision_check.cpp.
◆ start()
void moveit_servo::CollisionCheck::start |
( |
| ) |
|
◆ worstCaseStopTimeCB()
void moveit_servo::CollisionCheck::worstCaseStopTimeCB |
( |
const std_msgs::Float64ConstPtr & |
msg | ) |
|
|
private |
Callback for stopping time, from the thread that is aware of velocity and acceleration.
Definition at line 203 of file collision_check.cpp.
◆ collision_check_type_
◆ collision_detected_
bool moveit_servo::CollisionCheck::collision_detected_ = false |
|
private |
◆ collision_request_
◆ collision_result_
◆ collision_velocity_scale_pub_
ros::Publisher moveit_servo::CollisionCheck::collision_velocity_scale_pub_ |
|
private |
◆ current_collision_distance_
double moveit_servo::CollisionCheck::current_collision_distance_ = 0 |
|
private |
◆ current_state_
robot_state::RobotStatePtr moveit_servo::CollisionCheck::current_state_ |
|
private |
◆ derivative_of_collision_distance_
double moveit_servo::CollisionCheck::derivative_of_collision_distance_ = 0 |
|
private |
◆ est_time_to_collision_
double moveit_servo::CollisionCheck::est_time_to_collision_ = 0 |
|
private |
◆ joint_state_sub_
◆ nh_
◆ parameters_
◆ paused_
bool moveit_servo::CollisionCheck::paused_ = false |
|
private |
◆ period_
◆ planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr moveit_servo::CollisionCheck::planning_scene_monitor_ |
|
private |
◆ prev_collision_distance_
double moveit_servo::CollisionCheck::prev_collision_distance_ = 0 |
|
private |
◆ safety_factor_
double moveit_servo::CollisionCheck::safety_factor_ = 1000 |
|
private |
◆ scene_collision_distance_
double moveit_servo::CollisionCheck::scene_collision_distance_ = 0 |
|
private |
◆ scene_velocity_scale_coefficient_
const double moveit_servo::CollisionCheck::scene_velocity_scale_coefficient_ |
|
private |
◆ self_collision_distance_
double moveit_servo::CollisionCheck::self_collision_distance_ = 0 |
|
private |
◆ self_velocity_scale_coefficient_
const double moveit_servo::CollisionCheck::self_velocity_scale_coefficient_ |
|
private |
◆ timer_
◆ velocity_scale_
double moveit_servo::CollisionCheck::velocity_scale_ = 1 |
|
private |
◆ worst_case_stop_time_
double moveit_servo::CollisionCheck::worst_case_stop_time_ = std::numeric_limits<double>::max() |
|
private |
◆ worst_case_stop_time_sub_
The documentation for this class was generated from the following files: