Public Member Functions | Protected Member Functions | Protected Attributes
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer Class Reference

Message handler that streams joint trajectories to the robot controller. More...

#include <joint_trajectory_streamer.h>

Inheritance diagram for industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer:
Inheritance graph
[legend]

List of all members.

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< JointTrajPtMessagecurrent_traj_
int min_buffer_size_
boost::mutex mutex_
TransferState state_
ros::Time streaming_start_
boost::thread * streaming_thread_

Detailed Description

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.


Constructor & Destructor Documentation

Default constructor.

Parameters:
min_buffer_sizeminimum 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.


Member Function Documentation

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.

Parameters:
connectionsimple message connection that will be used to send commands to robot (ALREADY INITIALIZED)
joint_nameslist of expected joint-names.
  • Count and order should match data sent to robot connection.
  • Use blank-name to insert a placeholder joint position (typ. 0.0).
  • Joints in the incoming JointTrajectory stream that are NOT listed here will be ignored.
velocity_limitsmap of maximum velocities for each joint
  • leave empty to lookup from URDF
Returns:
true on success, false otherwise (an invalid message type)

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.

Parameters:
msgJointTrajectory message from ROS trajectory-planner

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 66 of file joint_trajectory_streamer.cpp.

Send trajectory to robot, using this node's robot-connection. Specific method must be implemented in a derived class (e.g. streaming, download, etc.)

Parameters:
messagesList of SimpleMessage JointTrajPtMessages to send to robot.
Returns:
true on success, false otherwise

Implements industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 102 of file joint_trajectory_streamer.cpp.

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.

Parameters:
[in]trajROS JointTrajectory message
[out]msgslist of JointTrajPtMessages for sending to robot
Returns:
true on success, false otherwise

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 118 of file joint_trajectory_streamer.cpp.

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.


Member Data Documentation

Definition at line 112 of file joint_trajectory_streamer.h.

Definition at line 113 of file joint_trajectory_streamer.h.

Definition at line 116 of file joint_trajectory_streamer.h.

Definition at line 111 of file joint_trajectory_streamer.h.

Definition at line 114 of file joint_trajectory_streamer.h.

Definition at line 115 of file joint_trajectory_streamer.h.

Definition at line 110 of file joint_trajectory_streamer.h.


The documentation for this class was generated from the following files:


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Tue Jan 17 2017 21:10:11