Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer Class Reference

Message handler that streams joint trajectories to the robot controller. More...

#include <joint_trajectory_streamer.h>

Inheritance diagram for industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer:
Inheritance graph
[legend]

Public Member Functions

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 ()
 
- Public Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
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 ()
 

Protected Member Functions

void trajectoryStop ()
 Send a stop command to the robot. More...
 
- Protected Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
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...
 

Protected Attributes

int current_point_
 
std::vector< JointTrajPtMessagecurrent_traj_
 
int min_buffer_size_
 
boost::mutex mutex_
 
TransferState state_
 
ros::Time streaming_start_
 
boost::thread * streaming_thread_
 
- Protected Attributes inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
std::vector< std::string > all_joint_names_
 
SmplMsgConnectionconnection_
 
sensor_msgs::JointState cur_joint_pos_
 
double default_duration_
 
double default_joint_pos_
 
TcpClient default_tcp_connection_
 
double default_vel_ratio_
 
std::map< std::string, double > joint_vel_limits_
 
ros::NodeHandle node_
 
ros::ServiceServer srv_joint_trajectory_
 
ros::ServiceServer srv_stop_motion_
 
ros::Subscriber sub_cur_pos_
 
ros::Subscriber sub_joint_trajectory_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ JointTrajectoryStreamer()

industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::JointTrajectoryStreamer ( int  min_buffer_size = 1)
inline

Default constructor.

Parameters
min_buffer_sizeminimum 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 ( )

Definition at line 61 of file joint_trajectory_streamer.cpp.

Member Function Documentation

◆ init() [1/4]

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init

Initialize robot connection using specified method.

Parameters
connectionnew 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
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)

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
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_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_ipdefault IP address to use for robot connection [OPTIONAL]
  • this value will be used if ROS param "robot_ip_address" cannot be read
default_portdefault 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

Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and send commands to robot.

Parameters
msgJointTrajectory message from ROS trajectory-planner

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 66 of file joint_trajectory_streamer.cpp.

◆ send_to_robot()

bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::send_to_robot ( const std::vector< JointTrajPtMessage > &  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.)

Parameters
messagesList of SimpleMessage JointTrajPtMessages to send to robot.
Returns
true on success, false otherwise

Implements industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 110 of file joint_trajectory_streamer.cpp.

◆ streamingThread()

void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streamingThread ( )

Definition at line 144 of file joint_trajectory_streamer.cpp.

◆ trajectory_to_msgs()

bool industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectory_to_msgs ( const trajectory_msgs::JointTrajectoryConstPtr &  traj,
std::vector< JointTrajPtMessage > *  msgs 
)
virtual

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.

Parameters
[in]trajROS JointTrajectory message
[out]msgslist of JointTrajPtMessages for sending to robot
Returns
true on success, false otherwise

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 126 of file joint_trajectory_streamer.cpp.

◆ trajectoryStop()

void industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::trajectoryStop ( )
protectedvirtual

Send a stop command to the robot.

Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.

Definition at line 222 of file joint_trajectory_streamer.cpp.

Member Data Documentation

◆ current_point_

int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_point_
protected

Definition at line 121 of file joint_trajectory_streamer.h.

◆ current_traj_

std::vector<JointTrajPtMessage> industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::current_traj_
protected

Definition at line 122 of file joint_trajectory_streamer.h.

◆ min_buffer_size_

int industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::min_buffer_size_
protected

Definition at line 125 of file joint_trajectory_streamer.h.

◆ mutex_

boost::mutex industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::mutex_
protected

Definition at line 120 of file joint_trajectory_streamer.h.

◆ state_

TransferState industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::state_
protected

Definition at line 123 of file joint_trajectory_streamer.h.

◆ streaming_start_

ros::Time industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_start_
protected

Definition at line 124 of file joint_trajectory_streamer.h.

◆ streaming_thread_

boost::thread* industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::streaming_thread_
protected

Definition at line 119 of file joint_trajectory_streamer.h.


The documentation for this class was generated from the following files:


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Wed Mar 2 2022 00:24:59