46 #include <Eigen/Geometry> 49 #include <control_msgs/JointJog.h> 50 #include <geometry_msgs/TwistStamped.h> 51 #include <sensor_msgs/JointState.h> 52 #include <trajectory_msgs/JointTrajectory.h> 93 std::atomic_bool
drift_dimensions[6] = { ATOMIC_VAR_INIT(
false), ATOMIC_VAR_INIT(
false), ATOMIC_VAR_INIT(
false),
94 ATOMIC_VAR_INIT(
false), ATOMIC_VAR_INIT(
false), ATOMIC_VAR_INIT(
false) };
106 std::atomic_bool
control_dimensions[6] = { ATOMIC_VAR_INIT(
true), ATOMIC_VAR_INIT(
true), ATOMIC_VAR_INIT(
true),
107 ATOMIC_VAR_INIT(
true), ATOMIC_VAR_INIT(
true), ATOMIC_VAR_INIT(
true) };
bool publish_joint_accelerations
std::atomic< bool > stop_requested
bool have_nonzero_joint_cmd
double hard_stop_singularity_threshold
bool publish_joint_positions
ros::Time latest_nonzero_cmd_stamp
std::atomic< bool > paused
Eigen::Isometry3d tf_moveit_to_cmd_frame
double incoming_command_timeout
sensor_msgs::JointState joints
std::string planning_frame
double low_pass_filter_coeff
double joint_limit_margin
std::string command_out_type
std::atomic_bool drift_dimensions[6]
double collision_check_rate
trajectory_msgs::JointTrajectory outgoing_command
geometry_msgs::TwistStamped command_deltas
std::string cartesian_command_in_topic
std::string joint_command_in_topic
bool publish_joint_velocities
std::atomic_bool control_dimensions[6]
double lower_singularity_threshold
std::string robot_link_command_frame
int num_outgoing_halt_msgs_to_publish
double scene_collision_proximity_threshold
control_msgs::JointJog joint_command_deltas
double collision_velocity_scale
std::string move_group_name
bool have_nonzero_cartesian_cmd
std::string command_in_type
double self_collision_proximity_threshold
std::string command_out_topic
std::atomic< StatusCode > status