Message handler that streams joint trajectories to the robot controller. More...
#include <joint_trajectory_streamer.h>
Public Member Functions | |
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 void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg) |
Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and send commands to robot. | |
JointTrajectoryStreamer (int min_buffer_size=1) | |
Default constructor. | |
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 a derived class (e.g. streaming, download, etc.) | |
void | streamingThread () |
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. | |
~JointTrajectoryStreamer () | |
Protected Member Functions | |
void | trajectoryStop () |
Send a stop command to the robot. | |
Protected Attributes | |
int | current_point_ |
std::vector< JointTrajPtMessage > | current_traj_ |
int | min_buffer_size_ |
boost::mutex | mutex_ |
TransferState | state_ |
ros::Time | streaming_start_ |
boost::thread * | streaming_thread_ |
Message handler that streams joint trajectories to the robot controller.
THIS CLASS IS NOT THREAD-SAFE
Definition at line 66 of file joint_trajectory_streamer.h.
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::JointTrajectoryStreamer | ( | int | min_buffer_size = 1 | ) | [inline] |
Default constructor.
min_buffer_size | minimum number of points as required by robot implementation |
Definition at line 79 of file joint_trajectory_streamer.h.
Definition at line 61 of file joint_trajectory_streamer.cpp.
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::init | ( | SmplMsgConnection * | connection, |
const std::vector< std::string > & | joint_names, | ||
const std::map< std::string, double > & | velocity_limits = std::map<std::string, double>() |
||
) | [virtual] |
Class initializer.
connection | simple message connection that will be used to send commands to robot (ALREADY INITIALIZED) |
joint_names | list of expected joint-names.
|
velocity_limits | map of maximum velocities for each joint
|
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 41 of file joint_trajectory_streamer.cpp.
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::jointTrajectoryCB | ( | const trajectory_msgs::JointTrajectoryConstPtr & | msg | ) | [virtual] |
Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and send commands to robot.
msg | JointTrajectory message from ROS trajectory-planner |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 66 of file joint_trajectory_streamer.cpp.
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::send_to_robot | ( | const std::vector< JointTrajPtMessage > & | messages | ) | [virtual] |
Send trajectory to robot, using this node's robot-connection. Specific method must be implemented in a derived class (e.g. streaming, download, etc.)
messages | List of SimpleMessage JointTrajPtMessages to send to robot. |
Implements industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 102 of file joint_trajectory_streamer.cpp.
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streamingThread | ( | ) |
Definition at line 136 of file joint_trajectory_streamer.cpp.
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectory_to_msgs | ( | const trajectory_msgs::JointTrajectoryConstPtr & | traj, |
std::vector< JointTrajPtMessage > * | msgs | ||
) | [virtual] |
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.
[in] | traj | ROS JointTrajectory message |
[out] | msgs | list of JointTrajPtMessages for sending to robot |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 118 of file joint_trajectory_streamer.cpp.
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectoryStop | ( | ) | [protected, virtual] |
Send a stop command to the robot.
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 214 of file joint_trajectory_streamer.cpp.
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_point_ [protected] |
Definition at line 112 of file joint_trajectory_streamer.h.
std::vector<JointTrajPtMessage> industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_traj_ [protected] |
Definition at line 113 of file joint_trajectory_streamer.h.
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::min_buffer_size_ [protected] |
Definition at line 116 of file joint_trajectory_streamer.h.
boost::mutex industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::mutex_ [protected] |
Definition at line 111 of file joint_trajectory_streamer.h.
TransferState industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::state_ [protected] |
Definition at line 114 of file joint_trajectory_streamer.h.
ros::Time industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_start_ [protected] |
Definition at line 115 of file joint_trajectory_streamer.h.
boost::thread* industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_thread_ [protected] |
Definition at line 110 of file joint_trajectory_streamer.h.