Message handler that streams joint trajectories to the robot controller. Contains FS100-specific motion control commands. More...
#include <joint_trajectory_streamer.h>
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 |
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.
motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::MotomanJointTrajectoryStreamer | ( | int | robot_id = -1 | ) | [inline] |
Default constructor.
robot_id | robot group # on this controller (for multi-group systems) |
Definition at line 76 of file joint_trajectory_streamer.h.
motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::~MotomanJointTrajectoryStreamer | ( | ) |
Definition at line 72 of file joint_trajectory_streamer.cpp.
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.
[in] | seq | sequence # of this point in the overall trajectory |
[in] | pt | trajectory point data |
[out] | msg | message for sending to robot |
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.
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_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] |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 260 of file joint_trajectory_streamer.cpp.
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::send_to_robot | ( | const std::vector< SimpleMessage > & | 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 SimpleMessages to send to robot. |
Reimplemented from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.
Definition at line 144 of file joint_trajectory_streamer.cpp.
void motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::streamingThread | ( | ) | [virtual] |
Reimplemented from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.
Definition at line 153 of file joint_trajectory_streamer.cpp.
void motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::trajectoryStop | ( | ) | [protected, virtual] |
Reimplemented from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.
Definition at line 253 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.
MotomanMotionCtrl motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::motion_ctrl_ [protected] |
Definition at line 116 of file joint_trajectory_streamer.h.
const double motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::pos_stale_time_ = 1.0 [static, protected] |
Definition at line 112 of file joint_trajectory_streamer.h.
Definition at line 115 of file joint_trajectory_streamer.h.
const double motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::start_pos_tol_ = 1e-4 [static, protected] |
Definition at line 113 of file joint_trajectory_streamer.h.