moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit_servo::CollisionCheck Class Reference

#include <collision_check.h>

Public Member Functions

 CollisionCheck (const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &parameters, 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...
 

Detailed Description

Definition at line 54 of file collision_check.h.

Constructor & Destructor Documentation

◆ CollisionCheck()

moveit_servo::CollisionCheck::CollisionCheck ( const rclcpp::Node::SharedPtr &  node,
const ServoParameters::SharedConstPtr parameters,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor 
)

Constructor.

Parameters
parameterscommon settings of moveit_servo
planning_scene_monitorPSM should have scene monitor and state monitor already started when passed into this class

Definition at line 52 of file collision_check.cpp.

◆ ~CollisionCheck()

moveit_servo::CollisionCheck::~CollisionCheck ( )
inline

Definition at line 65 of file collision_check.h.

Member Function Documentation

◆ setPaused()

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.

Here is the caller graph for this function:

◆ start()

void moveit_servo::CollisionCheck::start ( )

start the Timer that regulates collision check rate

Definition at line 80 of file collision_check.cpp.


The documentation for this class was generated from the following files: