32 #ifndef MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H 33 #define MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H 42 #include "std_srvs/Trigger.h" 46 namespace joint_trajectory_streamer
71 using JointTrajectoryInterface::is_valid;
96 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
111 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
128 virtual bool send_to_robot(
const std::vector<SimpleMessage>& messages);
139 bool is_valid(
const trajectory_msgs::JointTrajectory &traj);
140 bool is_valid(
const motoman_msgs::DynamicJointTrajectory &traj);
163 std_srvs::Trigger::Response &res);
171 std_srvs::Trigger::Response &res);
177 #endif // MOTOMAN_DRIVER_JOINT_TRAJECTORY_STREAMER_H std::map< int, MotomanMotionCtrl > motion_ctrl_map_
virtual bool send_to_robot(const std::vector< SimpleMessage > &messages)
Send trajectory to robot, using this node's robot-connection. Specific method must be implemented in ...
~MotomanJointTrajectoryStreamer()
ros::ServiceServer disabler_
Service used to disable the robot controller. When disabled, all incoming goals are ignored...
virtual bool create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage *msg)
Create SimpleMessage for sending to the robot.
Wrapper class around Motoman-specific motion control commands.
MotomanJointTrajectoryStreamer(int robot_id=-1)
Default constructor.
static bool VectorToJointData(const std::vector< double > &vec, industrial::joint_data::JointData &joints)
Message handler that streams joint trajectories to the robot controller. Contains FS100-specific moti...
bool disableRobotCB(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Disable the robot. Response is true if the state was flipped or false if the state has not changed...
bool is_valid(const trajectory_msgs::JointTrajectory &traj)
bool enableRobotCB(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Enable the robot. Response is true if the state was flipped or false if the state has not changed...
virtual bool create_message_ex(int seq, const motoman_msgs::DynamicJointPoint &point, SimpleMessage *msg)
virtual bool init(SmplMsgConnection *connection, const std::vector< std::string > &joint_names, const std::map< std::string, double > &velocity_limits=std::map< std::string, double >())
virtual void streamingThread()
MotomanMotionCtrl motion_ctrl_
ros::ServiceServer enabler_
Service used to enable the robot controller. When disabled, all incoming goals are ignored...
virtual bool init(SmplMsgConnection *connection, const std::vector< std::string > &joint_names, const std::map< std::string, double > &velocity_limits=std::map< std::string, double >())
Class initializer.
Message handler that streams joint trajectories to the robot controller.