Message handler that streams joint trajectories to the robot controller.
More...
#include <joint_trajectory_streamer.h>
|
void | trajectoryStop () |
| Send a stop command to the robot. More...
|
|
virtual bool | calc_duration (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_duration) |
| Compute the expected move duration for communication to the robot. If unneeded by the robot server, set to 0 (or any value). More...
|
|
virtual bool | calc_speed (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity, double *rbt_duration) |
| Reduce the ROS velocity commands (per-joint velocities) to a single scalar for communication to the robot. For flexibility, the robot command message contains both "velocity" and "duration" fields. The specific robot implementation can utilize either or both of these fields, as appropriate. More...
|
|
virtual bool | calc_velocity (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity) |
| Reduce the ROS velocity commands (per-joint velocities) to a single scalar for communication to the robot. If unneeded by the robot server, set to 0 (or any value). More...
|
|
virtual bool | is_valid (const trajectory_msgs::JointTrajectory &traj) |
| Validate that trajectory command meets minimum requirements. More...
|
|
virtual void | jointStateCB (const sensor_msgs::JointStateConstPtr &msg) |
|
virtual bool | select (const std::vector< std::string > &ros_joint_names, const trajectory_msgs::JointTrajectoryPoint &ros_pt, const std::vector< std::string > &rbt_joint_names, trajectory_msgs::JointTrajectoryPoint *rbt_pt) |
| Select specific joints for sending to the robot. More...
|
|
virtual bool | stopMotionCB (industrial_msgs::StopMotion::Request &req, industrial_msgs::StopMotion::Response &res) |
| Callback function registered to ROS stopMotion service Sends stop-motion command to robot. More...
|
|
virtual bool | transform (const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out) |
| Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling. More...
|
|
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.
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::JointTrajectoryStreamer |
( |
int |
min_buffer_size = 1 | ) |
|
|
inline |
Default constructor.
- Parameters
-
min_buffer_size | minimum number of points as required by robot implementation |
Definition at line 79 of file joint_trajectory_streamer.h.
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::~JointTrajectoryStreamer |
( |
| ) |
|
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
-
connection | simple message connection that will be used to send commands to robot (ALREADY INITIALIZED) |
joint_names | list 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_limits | map 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 |
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::send_to_robot |
( |
const std::vector< JointTrajPtMessage > & |
messages | ) |
|
|
virtual |
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streamingThread |
( |
| ) |
|
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectory_to_msgs |
( |
const trajectory_msgs::JointTrajectoryConstPtr & |
traj, |
|
|
std::vector< JointTrajPtMessage > * |
msgs |
|
) |
| |
|
virtual |
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectoryStop |
( |
| ) |
|
|
protectedvirtual |
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_point_ |
|
protected |
std::vector<JointTrajPtMessage> industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_traj_ |
|
protected |
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::min_buffer_size_ |
|
protected |
boost::mutex industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::mutex_ |
|
protected |
TransferState industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::state_ |
|
protected |
ros::Time industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_start_ |
|
protected |
boost::thread* industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_thread_ |
|
protected |
The documentation for this class was generated from the following files: