#include <jog_ros_interface.h>
Public Member Functions | |
JogROSInterface () | |
Private Member Functions | |
void | deltaCartesianCmdCB (const geometry_msgs::TwistStampedConstPtr &msg) |
void | deltaJointCmdCB (const control_msgs::JointJogConstPtr &msg) |
Additional Inherited Members | |
![]() | |
bool | readParameters (ros::NodeHandle &n) |
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... | |
![]() | |
std::unique_ptr< std::thread > | collision_check_thread_ |
std::unique_ptr< CollisionCheckThread > | collision_checker_ |
std::unique_ptr< std::thread > | jog_calc_thread_ |
std::unique_ptr< JogCalcs > | jog_calcs_ |
planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor_ |
JogArmParameters | ros_parameters_ |
JogArmShared | shared_variables_ |
Class JogROSInterface - Instantiated in main(). Handles ROS subs & pubs and creates the worker threads.
Definition at line 50 of file jog_ros_interface.h.
moveit_jog_arm::JogROSInterface::JogROSInterface | ( | ) |
Definition at line 55 of file jog_ros_interface.cpp.
|
private |
Definition at line 173 of file jog_ros_interface.cpp.
|
private |
Definition at line 204 of file jog_ros_interface.cpp.