#include <jog_cpp_interface.h>
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 () | |
![]() | |
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 | |
![]() | |
bool | readParameters (ros::NodeHandle &n) |
![]() | |
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 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.
moveit_jog_arm::JogCppInterface::JogCppInterface | ( | const planning_scene_monitor::PlanningSceneMonitorPtr & | planning_scene_monitor | ) |
Definition at line 46 of file jog_cpp_interface.cpp.
moveit_jog_arm::JogCppInterface::~JogCppInterface | ( | ) |
Definition at line 55 of file jog_cpp_interface.cpp.
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
transform | the transform that will be calculated |
Definition at line 215 of file jog_cpp_interface.cpp.
StatusCode moveit_jog_arm::JogCppInterface::getJoggerStatus | ( | ) |
Get the status of the jogger.
Definition at line 228 of file jog_cpp_interface.cpp.
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.
Definition at line 206 of file jog_cpp_interface.cpp.
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.
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.
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.
void moveit_jog_arm::JogCppInterface::startMainLoop | ( | ) |
Definition at line 60 of file jog_cpp_interface.cpp.
void moveit_jog_arm::JogCppInterface::stopMainLoop | ( | ) |
Definition at line 148 of file jog_cpp_interface.cpp.
|
private |
Definition at line 98 of file jog_cpp_interface.h.