Public Member Functions | Protected Member Functions | Static Protected Member Functions | 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 create_message (int seq, const motoman_msgs::DynamicJointsGroup &pt, SimpleMessage *msg)
virtual bool create_message_ex (int seq, const motoman_msgs::DynamicJointPoint &point, SimpleMessage *msg)
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 init (SmplMsgConnection *connection, const std::map< int, RobotGroup > &robot_groups, 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 disableRobotCB (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Disable the robot. Response is true if the state was flipped or false if the state has not changed.
bool enableRobotCB (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 Enable the robot. Response is true if the state was flipped or false if the state has not changed.
bool is_valid (const trajectory_msgs::JointTrajectory &traj)
bool is_valid (const motoman_msgs::DynamicJointTrajectory &traj)
 Validate that trajectory command meets minimum requirements.
void trajectoryStop ()

Static Protected Member Functions

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

Protected Attributes

ros::ServiceServer disabler_
 Service used to disable the robot controller. When disabled, all incoming goals are ignored.
ros::ServiceServer enabler_
 Service used to enable the robot controller. When disabled, all incoming goals are ignored.
MotomanMotionCtrl motion_ctrl_
std::map< int, MotomanMotionCtrlmotion_ctrl_map_
int robot_id_

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 65 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 78 of file joint_trajectory_streamer.h.

Definition at line 119 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 170 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::create_message ( int  seq,
const motoman_msgs::DynamicJointsGroup &  pt,
SimpleMessage msg 
) [virtual]
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::create_message_ex ( int  seq,
const motoman_msgs::DynamicJointPoint &  point,
SimpleMessage msg 
) [virtual]
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::disableRobotCB ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
) [protected]

Disable the robot. Response is true if the state was flipped or false if the state has not changed.

Definition at line 125 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::enableRobotCB ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
) [protected]

Enable the robot. Response is true if the state was flipped or false if the state has not changed.

Definition at line 148 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 97 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::init ( SmplMsgConnection connection,
const std::map< int, RobotGroup > &  robot_groups,
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 68 of file joint_trajectory_streamer.cpp.

bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::is_valid ( const trajectory_msgs::JointTrajectory &  traj) [protected, virtual]
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::is_valid ( const motoman_msgs::DynamicJointTrajectory &  traj) [protected, virtual]

Validate that trajectory command meets minimum requirements.

Parameters:
trajincoming trajectory
Returns:
true if trajectory is valid, false otherwise

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 509 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 SimpleMessages to send to robot.
Returns:
true on success, false otherwise

Reimplemented from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 369 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 353 of file joint_trajectory_streamer.cpp.


Member Data Documentation

Service used to disable the robot controller. When disabled, all incoming goals are ignored.

Definition at line 150 of file joint_trajectory_streamer.h.

Service used to enable the robot controller. When disabled, all incoming goals are ignored.

Definition at line 156 of file joint_trajectory_streamer.h.

Definition at line 135 of file joint_trajectory_streamer.h.

Definition at line 137 of file joint_trajectory_streamer.h.

Definition at line 134 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 Sat Jun 8 2019 19:06:58