Public Member Functions | Private Attributes | List of all members
moveit_jog_arm::JogCppInterface Class Reference

#include <jog_cpp_interface.h>

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

Public Member Functions

bool getCommandFrameTransform (Eigen::Isometry3d &transform)
 
StatusCode getJoggerStatus ()
 
sensor_msgs::JointState getJointState ()
 
 JogCppInterface (const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
 
void provideJointCommand (const control_msgs::JointJog &joint_command)
 Send joint position(s) commands. More...
 
void provideTwistStampedCommand (const geometry_msgs::TwistStamped &velocity_command)
 Provide a Cartesian velocity command to the jogger. The units are determined by settings in the yaml file. More...
 
void setPaused (bool paused)
 Pause or unpause processing jog commands while keeping the main loop alive. More...
 
void startMainLoop ()
 
void stopMainLoop ()
 
 ~JogCppInterface ()
 
- Public Member Functions inherited from moveit_jog_arm::JogInterfaceBase
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...
 

Private Attributes

ros::NodeHandle nh_
 

Additional Inherited Members

- Protected Member Functions inherited from moveit_jog_arm::JogInterfaceBase
bool readParameters (ros::NodeHandle &n)
 
- Protected Attributes inherited from moveit_jog_arm::JogInterfaceBase
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 JogCppInterface - This class should be instantiated in a new thread See cpp_interface_example.cpp

Definition at line 51 of file jog_cpp_interface.h.

Constructor & Destructor Documentation

◆ JogCppInterface()

moveit_jog_arm::JogCppInterface::JogCppInterface ( const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor)

Definition at line 46 of file jog_cpp_interface.cpp.

◆ ~JogCppInterface()

moveit_jog_arm::JogCppInterface::~JogCppInterface ( )

Definition at line 55 of file jog_cpp_interface.cpp.

Member Function Documentation

◆ getCommandFrameTransform()

bool moveit_jog_arm::JogCppInterface::getCommandFrameTransform ( Eigen::Isometry3d &  transform)

Get the MoveIt planning link transform. The transform from the MoveIt planning frame to robot_link_command_frame

Parameters
transformthe transform that will be calculated
Returns
true if a valid transform was available

Definition at line 215 of file jog_cpp_interface.cpp.

◆ getJoggerStatus()

StatusCode moveit_jog_arm::JogCppInterface::getJoggerStatus ( )

Get the status of the jogger.

Returns
0 for no warning. The meaning of nonzero values can be seen in status_codes.h

Definition at line 228 of file jog_cpp_interface.cpp.

◆ getJointState()

sensor_msgs::JointState moveit_jog_arm::JogCppInterface::getJointState ( )

Returns the most recent JointState that the jogger has received. May eliminate the need to create your own joint_state subscriber.

Returns
the most recent joints known to the jogger

Definition at line 206 of file jog_cpp_interface.cpp.

◆ provideJointCommand()

void moveit_jog_arm::JogCppInterface::provideJointCommand ( const control_msgs::JointJog &  joint_command)

Send joint position(s) commands.

Definition at line 186 of file jog_cpp_interface.cpp.

◆ provideTwistStampedCommand()

void moveit_jog_arm::JogCppInterface::provideTwistStampedCommand ( const geometry_msgs::TwistStamped &  velocity_command)

Provide a Cartesian velocity command to the jogger. The units are determined by settings in the yaml file.

Definition at line 158 of file jog_cpp_interface.cpp.

◆ setPaused()

void moveit_jog_arm::JogCppInterface::setPaused ( bool  paused)

Pause or unpause processing jog commands while keeping the main loop alive.

Definition at line 153 of file jog_cpp_interface.cpp.

◆ startMainLoop()

void moveit_jog_arm::JogCppInterface::startMainLoop ( )

Definition at line 60 of file jog_cpp_interface.cpp.

◆ stopMainLoop()

void moveit_jog_arm::JogCppInterface::stopMainLoop ( )

Definition at line 148 of file jog_cpp_interface.cpp.

Member Data Documentation

◆ nh_

ros::NodeHandle moveit_jog_arm::JogCppInterface::nh_
private

Definition at line 98 of file jog_cpp_interface.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