38 namespace joint_trajectory_streamer
42 const std::map<std::string, double> &velocity_limits)
46 ROS_INFO(
"JointTrajectoryStreamer: init");
68 ROS_INFO(
"Receiving joint trajectory message");
71 const auto state = this->
state_;
80 if (msg->points.empty())
94 ROS_ERROR(
"Trajectory splicing not yet implemented, stopping current motion.");
102 std::vector<JointTrajPtMessage> new_traj_msgs;
112 ROS_INFO(
"Loading trajectory, setting state to streaming");
115 ROS_INFO(
"Executing trajectory of size: %d", (
int)messages.size());
137 msgs->push_back(msgs->back());
147 int connectRetryCount = 1;
149 ROS_INFO(
"Starting joint trajectory streamer thread");
155 if (connectRetryCount-- > 0)
157 ROS_INFO(
"Connecting to robot motion server");
162 connectRetryCount = 0;
163 else if (connectRetryCount <= 0)
165 ROS_ERROR(
"Timeout connecting to robot controller. Send new motion command to retry.");
184 ROS_INFO(
"Trajectory streaming complete, setting state to IDLE");
191 ROS_DEBUG(
"Robot disconnected. Attempting reconnect...");
192 connectRetryCount = 5;
199 ROS_DEBUG(
"Sending joint trajectory point");
203 ROS_INFO(
"Point[%d of %d] sent to controller",
207 ROS_WARN(
"Failed sent joint point, will try again");
211 ROS_ERROR(
"Joint trajectory streamer: unknown state");
219 ROS_WARN(
"Exiting trajectory streamer thread");
226 ROS_DEBUG(
"Stop command sent, entering idle mode");
SmplMsgConnection * connection_
virtual bool toRequest(industrial::simple_message::SimpleMessage &msg)
void trajectoryStop()
Send a stop command to the robot.
ros::Time streaming_start_
bool sendAndReceiveMsg(industrial::simple_message::SimpleMessage &send, industrial::simple_message::SimpleMessage &recv, bool verbose=false)
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 ...
virtual bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
Initialize robot connection using default method.
virtual void trajectoryStop()
Send a stop command to the robot.
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.
virtual bool isConnected()=0
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_
#define ROS_INFO_STREAM(args)
std::string to_string(TransferState state)
~JointTrajectoryStreamer()
boost::thread * streaming_thread_
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. Also includes various joint transforms that can be overridden for robot-specific behavior.
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. Also includes various joint transforms that can be overridden for robot-specific behavior.
virtual bool makeConnect()=0