Message handler that streams joint trajectories to the robot controller.
More...
#include <joint_trajectory_streamer.h>
|
virtual bool | init (SmplMsgConnection *connection) |
| Initialize robot connection using specified method. More...
|
|
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. More...
|
|
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. More...
|
|
virtual bool | init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION) |
| Initialize robot connection using default method. More...
|
|
virtual void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg) |
| Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and send commands to robot. More...
|
|
| JointTrajectoryStreamer (int min_buffer_size=1) |
| Default constructor. More...
|
|
bool | send_to_robot (const std::vector< JointTrajPtMessage > &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.) More...
|
|
void | streamingThread () |
|
virtual bool | trajectory_to_msgs (const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs) |
| Convert ROS trajectory message into stream of JointTrajPtMessages for sending to robot. Also includes various joint transforms that can be overridden for robot-specific behavior. More...
|
|
| ~JointTrajectoryStreamer () |
|
virtual bool | init (SmplMsgConnection *connection) |
| Initialize robot connection using specified method. More...
|
|
virtual bool | init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION) |
| Initialize robot connection using default method. More...
|
|
| JointTrajectoryInterface () |
| Default constructor. More...
|
|
virtual void | run () |
| Begin processing messages and publishing topics. More...
|
|
virtual | ~JointTrajectoryInterface () |
|
|
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 75 of file joint_trajectory_streamer.h.
◆ JointTrajectoryStreamer()
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 88 of file joint_trajectory_streamer.h.
◆ ~JointTrajectoryStreamer()
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::~JointTrajectoryStreamer |
( |
| ) |
|
◆ init() [1/4]
bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init |
Initialize robot connection using specified method.
- Parameters
-
connection | new robot-connection instance (ALREADY INITIALIZED). |
- Returns
- true on success, false otherwise
Definition at line 80 of file joint_trajectory_interface.cpp.
◆ init() [2/4]
bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init |
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)
Definition at line 92 of file joint_trajectory_interface.cpp.
◆ init() [3/4]
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.
◆ init() [4/4]
bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init |
Initialize robot connection using default method.
- Parameters
-
default_ip | default IP address to use for robot connection [OPTIONAL]
- this value will be used if ROS param "robot_ip_address" cannot be read
|
default_port | default port to use for robot connection [OPTIONAL]
- this value will be used if ROS param "~port" cannot be read
|
- Returns
- true on success, false otherwise
Definition at line 51 of file joint_trajectory_interface.cpp.
◆ jointTrajectoryCB()
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::jointTrajectoryCB |
( |
const trajectory_msgs::JointTrajectoryConstPtr & |
msg | ) |
|
|
virtual |
◆ send_to_robot()
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::send_to_robot |
( |
const std::vector< JointTrajPtMessage > & |
messages | ) |
|
|
virtual |
◆ streamingThread()
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streamingThread |
( |
| ) |
|
◆ trajectory_to_msgs()
bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectory_to_msgs |
( |
const trajectory_msgs::JointTrajectoryConstPtr & |
traj, |
|
|
std::vector< JointTrajPtMessage > * |
msgs |
|
) |
| |
|
virtual |
◆ trajectoryStop()
void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectoryStop |
( |
| ) |
|
|
protectedvirtual |
◆ current_point_
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_point_ |
|
protected |
◆ current_traj_
std::vector<JointTrajPtMessage> industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_traj_ |
|
protected |
◆ min_buffer_size_
int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::min_buffer_size_ |
|
protected |
◆ mutex_
boost::mutex industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::mutex_ |
|
protected |
◆ state_
TransferState industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::state_ |
|
protected |
◆ streaming_start_
ros::Time industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_start_ |
|
protected |
◆ streaming_thread_
boost::thread* industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_thread_ |
|
protected |
The documentation for this class was generated from the following files: