Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer Class Reference

Message handler that streams joint trajectories to the robot controller. Contains FS100-specific motion control commands. More...

#include <joint_trajectory_streamer.h>

Inheritance diagram for motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool create_message (int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage *msg)
 Create SimpleMessage for sending 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.
 MotomanJointTrajectoryStreamer (int robot_id=-1)
 Default constructor.
virtual bool send_to_robot (const std::vector< SimpleMessage > &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.)
virtual void streamingThread ()
 ~MotomanJointTrajectoryStreamer ()

Protected Member Functions

bool is_valid (const trajectory_msgs::JointTrajectory &traj)
void trajectoryStop ()

Static Protected Member Functions

static bool VectorToJointData (const std::vector< double > &vec, industrial::joint_data::JointData &joints)

Protected Attributes

MotomanMotionCtrl motion_ctrl_
int robot_id_

Static Protected Attributes

static const double pos_stale_time_ = 1.0
static const double start_pos_tol_ = 1e-4

Detailed Description

Message handler that streams joint trajectories to the robot controller. Contains FS100-specific motion control commands.

THIS CLASS IS NOT THREAD-SAFE

Definition at line 61 of file joint_trajectory_streamer.h.


Constructor & Destructor Documentation

Default constructor.

Parameters:
robot_idrobot group # on this controller (for multi-group systems)

Definition at line 76 of file joint_trajectory_streamer.h.

Definition at line 72 of file joint_trajectory_streamer.cpp.


Member Function Documentation

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::create_message ( int  seq,
const trajectory_msgs::JointTrajectoryPoint &  pt,
SimpleMessage msg 
) [virtual]

Create SimpleMessage for sending to the robot.

Parameters:
[in]seqsequence # of this point in the overall trajectory
[in]pttrajectory point data
[out]msgmessage for sending to robot
Returns:
true on success, false otherwise

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 79 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::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_streamer::JointTrajectoryStreamer.

Definition at line 54 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::is_valid ( const trajectory_msgs::JointTrajectory &  traj) [protected, 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.)

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

Reimplemented from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 144 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::VectorToJointData ( const std::vector< double > &  vec,
industrial::joint_data::JointData joints 
) [static, protected]

Definition at line 129 of file joint_trajectory_streamer.cpp.


Member Data Documentation

Definition at line 116 of file joint_trajectory_streamer.h.

Definition at line 112 of file joint_trajectory_streamer.h.

Definition at line 115 of file joint_trajectory_streamer.h.

Definition at line 113 of file joint_trajectory_streamer.h.


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


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Wed Aug 26 2015 12:37:34