Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit_jog_arm::JogInterfaceBase Class Reference

#include <jog_interface_base.h>

Inheritance diagram for moveit_jog_arm::JogInterfaceBase:
Inheritance graph
[legend]

Public Member Functions

bool changeControlDimensions (moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
 Start the main calculation thread. More...
 
bool changeDriftDimensions (moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
 
 JogInterfaceBase ()
 
void jointsCB (const sensor_msgs::JointStateConstPtr &msg)
 Update the joints of the robot. More...
 
bool startCollisionCheckThread ()
 Start collision checking. More...
 
bool startJogCalcThread ()
 
bool stopCollisionCheckThread ()
 Stop collision checking. More...
 
bool stopJogCalcThread ()
 Stop the main calculation thread. More...
 

Protected Member Functions

bool readParameters (ros::NodeHandle &n)
 

Protected Attributes

std::unique_ptr< std::thread > collision_check_thread_
 
std::unique_ptr< CollisionCheckThreadcollision_checker_
 
std::unique_ptr< std::thread > jog_calc_thread_
 
std::unique_ptr< JogCalcsjog_calcs_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
JogArmParameters ros_parameters_
 
JogArmShared shared_variables_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ JogInterfaceBase()

moveit_jog_arm::JogInterfaceBase::JogInterfaceBase ( )

Definition at line 46 of file jog_interface_base.cpp.

Member Function Documentation

◆ changeControlDimensions()

bool moveit_jog_arm::JogInterfaceBase::changeControlDimensions ( moveit_msgs::ChangeControlDimensions::Request &  req,
moveit_msgs::ChangeControlDimensions::Response &  res 
)

Start the main calculation thread.

Definition at line 264 of file jog_interface_base.cpp.

◆ 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
requestthe service request
responsethe 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)

Update the joints of the robot.

Definition at line 242 of file jog_interface_base.cpp.

◆ readParameters()

bool moveit_jog_arm::JogInterfaceBase::readParameters ( ros::NodeHandle n)
protected

Definition at line 51 of file jog_interface_base.cpp.

◆ startCollisionCheckThread()

bool moveit_jog_arm::JogInterfaceBase::startCollisionCheckThread ( )

Start collision checking.

Definition at line 303 of file jog_interface_base.cpp.

◆ startJogCalcThread()

bool moveit_jog_arm::JogInterfaceBase::startJogCalcThread ( )

Definition at line 279 of file jog_interface_base.cpp.

◆ stopCollisionCheckThread()

bool moveit_jog_arm::JogInterfaceBase::stopCollisionCheckThread ( )

Stop collision checking.

Definition at line 313 of file jog_interface_base.cpp.

◆ stopJogCalcThread()

bool moveit_jog_arm::JogInterfaceBase::stopJogCalcThread ( )

Stop the main calculation thread.

Definition at line 289 of file jog_interface_base.cpp.

Member Data Documentation

◆ collision_check_thread_

std::unique_ptr<std::thread> moveit_jog_arm::JogInterfaceBase::collision_check_thread_
protected

Definition at line 111 of file jog_interface_base.h.

◆ collision_checker_

std::unique_ptr<CollisionCheckThread> moveit_jog_arm::JogInterfaceBase::collision_checker_
protected

Definition at line 110 of file jog_interface_base.h.

◆ jog_calc_thread_

std::unique_ptr<std::thread> moveit_jog_arm::JogInterfaceBase::jog_calc_thread_
protected

Definition at line 107 of file jog_interface_base.h.

◆ jog_calcs_

std::unique_ptr<JogCalcs> moveit_jog_arm::JogInterfaceBase::jog_calcs_
protected

Definition at line 106 of file jog_interface_base.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr moveit_jog_arm::JogInterfaceBase::planning_scene_monitor_
protected

Definition at line 97 of file jog_interface_base.h.

◆ ros_parameters_

JogArmParameters moveit_jog_arm::JogInterfaceBase::ros_parameters_
protected

Definition at line 100 of file jog_interface_base.h.

◆ shared_variables_

JogArmShared moveit_jog_arm::JogInterfaceBase::shared_variables_
protected

Definition at line 103 of file jog_interface_base.h.


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


moveit_jog_arm
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Alexander Rössler
autogenerated on Fri Jun 5 2020 03:53:46