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);
111 void streamingThread();
113 bool send_to_robot(
const std::vector<JointTrajPtMessage>& messages);
117 void trajectoryStop();
void init(const M_string &remappings)
Message handler that relays joint trajectories to the robot controller.
ros::Time streaming_start_
virtual bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
Initialize robot connection using default method.
JointTrajectoryStreamer(int min_buffer_size=1)
Default constructor.
std::vector< JointTrajPtMessage > current_traj_
std::string to_string(TransferState state)
boost::thread * streaming_thread_
Message handler that streams joint trajectories to the robot controller.