Go to the documentation of this file.
41 #include <moveit/collision_detection/collision_common.h>
44 #include <sensor_msgs/JointState.h>
45 #include <std_msgs/Float64.h>
const ServoParameters & parameters_
void setPaused(bool paused)
Pause or unpause processing servo commands while keeping the timers alive.
robot_state::RobotStatePtr current_state_
void start()
start the Timer that regulates collision check rate
const double self_velocity_scale_coefficient_
const double scene_velocity_scale_coefficient_
double prev_collision_distance_
double current_collision_distance_
CollisionCheck(ros::NodeHandle &nh, const moveit_servo::ServoParameters ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor.
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
collision_detection::CollisionResult collision_result_
collision_detection::CollisionRequest collision_request_
ros::Subscriber worst_case_stop_time_sub_
void run(const ros::TimerEvent &timer_event)
Run one iteration of collision checking.
double est_time_to_collision_
ros::Subscriber joint_state_sub_
double worst_case_stop_time_
double scene_collision_distance_
void worstCaseStopTimeCB(const std_msgs::Float64ConstPtr &msg)
Callback for stopping time, from the thread that is aware of velocity and acceleration.
CollisionCheckType collision_check_type_
double self_collision_distance_
planning_scene_monitor::LockedPlanningSceneRO getLockedPlanningSceneRO() const
Get a read-only copy of the planning scene.
ros::Publisher collision_velocity_scale_pub_
double derivative_of_collision_distance_
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