42 static const std::string
LOGNAME =
"jog_cpp_interface";
116 outgoing_cmd_pub.
publish(outgoing_command);
120 std_msgs::Float64MultiArray joints;
122 joints.data = outgoing_command.points[0].positions;
124 joints.data = outgoing_command.points[0].velocities;
125 outgoing_cmd_pub.
publish(joints);
131 "Try a larger 'incoming_command_timeout' parameter?");
192 bool all_zeros =
true;
195 all_zeros &= (delta == 0.0);
212 return current_joints;
225 return !transform.matrix().isZero(0);
std::atomic< bool > stop_requested
bool have_nonzero_joint_cmd
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool publish_joint_positions
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Time latest_nonzero_cmd_stamp
StatusCode getJoggerStatus()
std::atomic< bool > paused
Eigen::Isometry3d tf_moveit_to_cmd_frame
#define ROS_INFO_STREAM_NAMED(name, args)
double incoming_command_timeout
static const std::string LOGNAME
sensor_msgs::JointState joints
bool startCollisionCheckThread()
Start collision checking.
void provideJointCommand(const control_msgs::JointJog &joint_command)
Send joint position(s) commands.
#define ROS_DEBUG_NAMED(name,...)
void setPaused(bool paused)
Pause or unpause processing jog commands while keeping the main loop alive.
std::string command_out_type
trajectory_msgs::JointTrajectory outgoing_command
geometry_msgs::TwistStamped command_deltas
void publish(const boost::shared_ptr< M > &message) const
bool publish_joint_velocities
std::unique_ptr< JogCalcs > jog_calcs_
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
JogArmShared shared_variables_
std::string robot_link_command_frame
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 ...
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool stopCollisionCheckThread()
Stop collision checking.
bool stopJogCalcThread()
Stop the main calculation thread.
control_msgs::JointJog joint_command_deltas
JogCppInterface(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
bool startJogCalcThread()
bool readParameters(ros::NodeHandle &n)
void jointsCB(const sensor_msgs::JointStateConstPtr &msg)
Update the joints of the robot.
bool have_nonzero_cartesian_cmd
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(period, name, args)
ROSCPP_DECL void spinOnce()
std::string command_out_topic
bool getCommandFrameTransform(Eigen::Isometry3d &transform)
sensor_msgs::JointState getJointState()
std::atomic< StatusCode > status
JogArmParameters ros_parameters_