#include <jog_arm_data.h>
Public Attributes | |
double | collision_velocity_scale = 1 |
geometry_msgs::TwistStamped | command_deltas |
bool | command_is_stale = false |
std::atomic_bool | control_dimensions [6] |
std::atomic_bool | drift_dimensions [6] |
bool | have_nonzero_cartesian_cmd = false |
bool | have_nonzero_joint_cmd = false |
control_msgs::JointJog | joint_command_deltas |
sensor_msgs::JointState | joints |
ros::Time | latest_nonzero_cmd_stamp = ros::Time(0.) |
bool | ok_to_publish = false |
trajectory_msgs::JointTrajectory | outgoing_command |
std::atomic< bool > | paused { false } |
std::atomic< StatusCode > | status |
std::atomic< bool > | stop_requested { false } |
Eigen::Isometry3d | tf_moveit_to_cmd_frame |
Definition at line 61 of file jog_arm_data.h.
double moveit_jog_arm::JogArmShared::collision_velocity_scale = 1 |
Definition at line 69 of file jog_arm_data.h.
geometry_msgs::TwistStamped moveit_jog_arm::JogArmShared::command_deltas |
Definition at line 63 of file jog_arm_data.h.
bool moveit_jog_arm::JogArmShared::command_is_stale = false |
Definition at line 78 of file jog_arm_data.h.
std::atomic_bool moveit_jog_arm::JogArmShared::control_dimensions[6] |
Definition at line 106 of file jog_arm_data.h.
std::atomic_bool moveit_jog_arm::JogArmShared::drift_dimensions[6] |
Definition at line 93 of file jog_arm_data.h.
bool moveit_jog_arm::JogArmShared::have_nonzero_cartesian_cmd = false |
Definition at line 72 of file jog_arm_data.h.
bool moveit_jog_arm::JogArmShared::have_nonzero_joint_cmd = false |
Definition at line 75 of file jog_arm_data.h.
control_msgs::JointJog moveit_jog_arm::JogArmShared::joint_command_deltas |
Definition at line 65 of file jog_arm_data.h.
sensor_msgs::JointState moveit_jog_arm::JogArmShared::joints |
Definition at line 67 of file jog_arm_data.h.
Definition at line 84 of file jog_arm_data.h.
bool moveit_jog_arm::JogArmShared::ok_to_publish = false |
Definition at line 87 of file jog_arm_data.h.
trajectory_msgs::JointTrajectory moveit_jog_arm::JogArmShared::outgoing_command |
Definition at line 81 of file jog_arm_data.h.
std::atomic<bool> moveit_jog_arm::JogArmShared::paused { false } |
Definition at line 100 of file jog_arm_data.h.
std::atomic<StatusCode> moveit_jog_arm::JogArmShared::status |
Definition at line 97 of file jog_arm_data.h.
std::atomic<bool> moveit_jog_arm::JogArmShared::stop_requested { false } |
Definition at line 103 of file jog_arm_data.h.
Eigen::Isometry3d moveit_jog_arm::JogArmShared::tf_moveit_to_cmd_frame |
Definition at line 90 of file jog_arm_data.h.