#include <jog_interface_base.h>
Class JogInterfaceBase - Base class for C++ interface and ROS node. Handles ROS subs & pubs and creates the worker threads.
Definition at line 57 of file jog_interface_base.h.
◆ JogInterfaceBase()
moveit_jog_arm::JogInterfaceBase::JogInterfaceBase |
( |
| ) |
|
◆ changeControlDimensions()
bool moveit_jog_arm::JogInterfaceBase::changeControlDimensions |
( |
moveit_msgs::ChangeControlDimensions::Request & |
req, |
|
|
moveit_msgs::ChangeControlDimensions::Response & |
res |
|
) |
| |
◆ changeDriftDimensions()
bool moveit_jog_arm::JogInterfaceBase::changeDriftDimensions |
( |
moveit_msgs::ChangeDriftDimensions::Request & |
req, |
|
|
moveit_msgs::ChangeDriftDimensions::Response & |
res |
|
) |
| |
Allow drift in certain dimensions. For example, may allow the wrist to rotate freely. This can help avoid singularities.
- Parameters
-
request | the service request |
response | the service response |
- Returns
- true if the adjustment was made
Definition at line 249 of file jog_interface_base.cpp.
◆ jointsCB()
void moveit_jog_arm::JogInterfaceBase::jointsCB |
( |
const sensor_msgs::JointStateConstPtr & |
msg | ) |
|
◆ readParameters()
bool moveit_jog_arm::JogInterfaceBase::readParameters |
( |
ros::NodeHandle & |
n | ) |
|
|
protected |
◆ startCollisionCheckThread()
bool moveit_jog_arm::JogInterfaceBase::startCollisionCheckThread |
( |
| ) |
|
◆ startJogCalcThread()
bool moveit_jog_arm::JogInterfaceBase::startJogCalcThread |
( |
| ) |
|
◆ stopCollisionCheckThread()
bool moveit_jog_arm::JogInterfaceBase::stopCollisionCheckThread |
( |
| ) |
|
◆ stopJogCalcThread()
bool moveit_jog_arm::JogInterfaceBase::stopJogCalcThread |
( |
| ) |
|
◆ collision_check_thread_
std::unique_ptr<std::thread> moveit_jog_arm::JogInterfaceBase::collision_check_thread_ |
|
protected |
◆ collision_checker_
◆ jog_calc_thread_
std::unique_ptr<std::thread> moveit_jog_arm::JogInterfaceBase::jog_calc_thread_ |
|
protected |
◆ jog_calcs_
std::unique_ptr<JogCalcs> moveit_jog_arm::JogInterfaceBase::jog_calcs_ |
|
protected |
◆ planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr moveit_jog_arm::JogInterfaceBase::planning_scene_monitor_ |
|
protected |
◆ ros_parameters_
◆ shared_variables_
JogArmShared moveit_jog_arm::JogInterfaceBase::shared_variables_ |
|
protected |
The documentation for this class was generated from the following files: