Go to the documentation of this file.
32 #ifndef JOINT_TRAJECTORY_STREAMER_H
33 #define JOINT_TRAJECTORY_STREAMER_H
35 #include <boost/thread/thread.hpp>
40 namespace joint_trajectory_streamer
47 namespace TransferStates
103 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
107 virtual void jointTrajectoryCB(
const trajectory_msgs::JointTrajectoryConstPtr &msg);
109 virtual bool trajectory_to_msgs(
const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<JointTrajPtMessage>* msgs);
113 bool send_to_robot(
const std::vector<JointTrajPtMessage>& messages);
bool send_to_robot(const std::vector< JointTrajPtMessage > &messages)
Send trajectory to robot, using this node's robot-connection. Specific method must be implemented in ...
Message handler that streams joint trajectories to the robot controller.
TransferStates::TransferState TransferState
void trajectoryStop()
Send a stop command to the robot.
std::string to_string(TransferState state)
~JointTrajectoryStreamer()
ros::Time streaming_start_
virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and...
std::vector< JointTrajPtMessage > current_traj_
virtual bool trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs)
Convert ROS trajectory message into stream of JointTrajPtMessages for sending to robot....
Message handler that relays joint trajectories to the robot controller.
virtual bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
Initialize robot connection using default method.
boost::thread * streaming_thread_
JointTrajectoryStreamer(int min_buffer_size=1)
Default constructor.
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.