Public Attributes | List of all members
moveit_jog_arm::JogArmShared Struct Reference

#include <jog_arm_data.h>

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

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< StatusCodestatus
 
std::atomic< bool > stop_requested { false }
 
Eigen::Isometry3d tf_moveit_to_cmd_frame
 

Detailed Description

Definition at line 61 of file jog_arm_data.h.

Member Data Documentation

◆ collision_velocity_scale

double moveit_jog_arm::JogArmShared::collision_velocity_scale = 1

Definition at line 69 of file jog_arm_data.h.

◆ command_deltas

geometry_msgs::TwistStamped moveit_jog_arm::JogArmShared::command_deltas

Definition at line 63 of file jog_arm_data.h.

◆ command_is_stale

bool moveit_jog_arm::JogArmShared::command_is_stale = false

Definition at line 78 of file jog_arm_data.h.

◆ control_dimensions

std::atomic_bool moveit_jog_arm::JogArmShared::control_dimensions[6]
Initial value:
= { ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true),
ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true), ATOMIC_VAR_INIT(true) }

Definition at line 106 of file jog_arm_data.h.

◆ drift_dimensions

std::atomic_bool moveit_jog_arm::JogArmShared::drift_dimensions[6]
Initial value:
= { ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false),
ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false), ATOMIC_VAR_INIT(false) }

Definition at line 93 of file jog_arm_data.h.

◆ have_nonzero_cartesian_cmd

bool moveit_jog_arm::JogArmShared::have_nonzero_cartesian_cmd = false

Definition at line 72 of file jog_arm_data.h.

◆ have_nonzero_joint_cmd

bool moveit_jog_arm::JogArmShared::have_nonzero_joint_cmd = false

Definition at line 75 of file jog_arm_data.h.

◆ joint_command_deltas

control_msgs::JointJog moveit_jog_arm::JogArmShared::joint_command_deltas

Definition at line 65 of file jog_arm_data.h.

◆ joints

sensor_msgs::JointState moveit_jog_arm::JogArmShared::joints

Definition at line 67 of file jog_arm_data.h.

◆ latest_nonzero_cmd_stamp

ros::Time moveit_jog_arm::JogArmShared::latest_nonzero_cmd_stamp = ros::Time(0.)

Definition at line 84 of file jog_arm_data.h.

◆ ok_to_publish

bool moveit_jog_arm::JogArmShared::ok_to_publish = false

Definition at line 87 of file jog_arm_data.h.

◆ outgoing_command

trajectory_msgs::JointTrajectory moveit_jog_arm::JogArmShared::outgoing_command

Definition at line 81 of file jog_arm_data.h.

◆ paused

std::atomic<bool> moveit_jog_arm::JogArmShared::paused { false }

Definition at line 100 of file jog_arm_data.h.

◆ status

std::atomic<StatusCode> moveit_jog_arm::JogArmShared::status

Definition at line 97 of file jog_arm_data.h.

◆ stop_requested

std::atomic<bool> moveit_jog_arm::JogArmShared::stop_requested { false }

Definition at line 103 of file jog_arm_data.h.

◆ tf_moveit_to_cmd_frame

Eigen::Isometry3d moveit_jog_arm::JogArmShared::tf_moveit_to_cmd_frame

Definition at line 90 of file jog_arm_data.h.


The documentation for this struct was generated from the following file:


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