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 | 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, MotomanMotionCtrl > | motion_ctrl_map_ |
int | robot_id_ |
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.
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 78 of file joint_trajectory_streamer.h.
motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::~MotomanJointTrajectoryStreamer | ( | ) |
Definition at line 119 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 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] |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 303 of file joint_trajectory_streamer.cpp.
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::create_message_ex | ( | int | seq, |
const motoman_msgs::DynamicJointPoint & | point, | ||
SimpleMessage * | msg | ||
) | [virtual] |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 221 of file joint_trajectory_streamer.cpp.
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.
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 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.
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 68 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 481 of file joint_trajectory_streamer.cpp.
bool motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::is_valid | ( | const motoman_msgs::DynamicJointTrajectory & | traj | ) | [protected, virtual] |
Validate that trajectory command meets minimum requirements.
traj | incoming trajectory |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 509 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 369 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 378 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 474 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.
ros::ServiceServer motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::disabler_ [protected] |
Service used to disable the robot controller. When disabled, all incoming goals are ignored.
Definition at line 150 of file joint_trajectory_streamer.h.
ros::ServiceServer motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::enabler_ [protected] |
Service used to enable the robot controller. When disabled, all incoming goals are ignored.
Definition at line 156 of file joint_trajectory_streamer.h.
MotomanMotionCtrl motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::motion_ctrl_ [protected] |
Definition at line 135 of file joint_trajectory_streamer.h.
std::map<int, MotomanMotionCtrl> motoman::joint_trajectory_streamer::MotomanJointTrajectoryStreamer::motion_ctrl_map_ [protected] |
Definition at line 137 of file joint_trajectory_streamer.h.
Definition at line 134 of file joint_trajectory_streamer.h.