44 static const std::string
LOGNAME =
"jog_ros_interface";
139 outgoing_cmd_pub.
publish(outgoing_command);
143 std_msgs::Float64MultiArray joints;
145 joints.data = outgoing_command.points[0].positions;
147 joints.data = outgoing_command.points[0].velocities;
148 outgoing_cmd_pub.
publish(joints);
154 "Try a larger 'incoming_command_timeout' parameter?");
210 bool all_zeros =
true;
213 all_zeros &= (delta == 0.0);
std::atomic< bool > stop_requested
bool have_nonzero_joint_cmd
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
#define ROS_ERROR_STREAM_NAMED(name, args)
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
static const std::string LOGNAME
ROSCPP_DECL const std::string & getName()
#define ROS_INFO_STREAM_NAMED(name, args)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
double incoming_command_timeout
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
void deltaCartesianCmdCB(const geometry_msgs::TwistStampedConstPtr &msg)
bool startCollisionCheckThread()
Start collision checking.
#define ROS_DEBUG_NAMED(name,...)
std::string command_out_type
trajectory_msgs::JointTrajectory outgoing_command
geometry_msgs::TwistStamped command_deltas
std::string cartesian_command_in_topic
void publish(const boost::shared_ptr< M > &message) const
std::string joint_command_in_topic
bool publish_joint_velocities
void deltaJointCmdCB(const control_msgs::JointJogConstPtr &msg)
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
JogArmShared shared_variables_
std::string robot_link_command_frame
bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request &req, moveit_msgs::ChangeDriftDimensions::Response &res)
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
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request &req, moveit_msgs::ChangeControlDimensions::Response &res)
Start the main calculation thread.
const std::string & getNamespace() const
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
JogArmParameters ros_parameters_