| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#include <collision_check.h>
Public Member Functions | |
| CollisionCheck (const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr ¶meters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor) | |
| Constructor.  More... | |
| ~CollisionCheck () | |
| void | start () | 
| start the Timer that regulates collision check rate  More... | |
| void | setPaused (bool paused) | 
| Pause or unpause processing servo commands while keeping the timers alive.  More... | |
Definition at line 54 of file collision_check.h.
| moveit_servo::CollisionCheck::CollisionCheck | ( | const rclcpp::Node::SharedPtr & | node, | 
| const ServoParameters::SharedConstPtr & | parameters, | ||
| const planning_scene_monitor::PlanningSceneMonitorPtr & | planning_scene_monitor | ||
| ) | 
Constructor.
| parameters | common settings of moveit_servo | 
| planning_scene_monitor | PSM should have scene monitor and state monitor already started when passed into this class | 
Definition at line 52 of file collision_check.cpp.
      
  | 
  inline | 
Definition at line 65 of file collision_check.h.
| void moveit_servo::CollisionCheck::setPaused | ( | bool | paused | ) | 
Pause or unpause processing servo commands while keeping the timers alive.
Definition at line 152 of file collision_check.cpp.

| void moveit_servo::CollisionCheck::start | ( | ) | 
start the Timer that regulates collision check rate
Definition at line 80 of file collision_check.cpp.