Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | List of all members
industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface Class Referenceabstract

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

#include <joint_trajectory_interface.h>

Inheritance diagram for industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface:
Inheritance graph
[legend]

Public Member Functions

virtual bool init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
 Initialize robot connection using default method. More...
 
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...
 
 JointTrajectoryInterface ()
 Default constructor. More...
 
virtual void run ()
 Begin processing messages and publishing topics. More...
 
virtual ~JointTrajectoryInterface ()
 

Protected Member Functions

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 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...
 
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 send_to_robot (const std::vector< JointTrajPtMessage > &messages)=0
 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...
 
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 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...
 
virtual void trajectoryStop ()
 Send a stop command to the 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

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_
 

Private Member Functions

bool jointTrajectoryCB (industrial_msgs::CmdJointTrajectory::Request &req, industrial_msgs::CmdJointTrajectory::Response &res)
 Callback function registered to ROS CmdJointTrajectory service Duplicates message-topic functionality, but in service form. More...
 

Static Private Member Functions

static JointTrajPtMessage create_message (int seq, std::vector< double > joint_pos, double velocity, double duration)
 

Detailed Description

Message handler that relays joint trajectories to the robot controller.

THIS CLASS IS NOT THREAD-SAFE

Definition at line 64 of file joint_trajectory_interface.h.

Constructor & Destructor Documentation

industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::JointTrajectoryInterface ( )
inline

Default constructor.

Definition at line 72 of file joint_trajectory_interface.h.

industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::~JointTrajectoryInterface ( )
virtual

Definition at line 112 of file joint_trajectory_interface.cpp.

Member Function Documentation

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::calc_duration ( const trajectory_msgs::JointTrajectoryPoint &  pt,
double *  rbt_duration 
)
protectedvirtual

Compute the expected move duration for communication to the robot. If unneeded by the robot server, set to 0 (or any value).

Parameters
[in]pttrajectory point data, in order/count expected by robot connection
[out]rbt_durationcomputed move duration for robot message (if needed by robot)
Returns
true on success, false otherwise

Definition at line 282 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::calc_speed ( const trajectory_msgs::JointTrajectoryPoint &  pt,
double *  rbt_velocity,
double *  rbt_duration 
)
protectedvirtual

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.

Parameters
[in]pttrajectory point data, in order/count expected by robot connection
[out]rbt_velocitycomputed velocity scalar for robot message (if needed by robot)
[out]rbt_durationcomputed move duration for robot message (if needed by robot)
Returns
true on success, false otherwise

Definition at line 224 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::calc_velocity ( const trajectory_msgs::JointTrajectoryPoint &  pt,
double *  rbt_velocity 
)
protectedvirtual

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).

Parameters
[in]pttrajectory point data, in order/count expected by robot connection
[out]rbt_velocitycomputed velocity scalar for robot message (if needed by robot)
Returns
true on success, false otherwise

Definition at line 235 of file joint_trajectory_interface.cpp.

JointTrajPtMessage industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::create_message ( int  seq,
std::vector< double >  joint_pos,
double  velocity,
double  duration 
)
staticprivate

Definition at line 298 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init ( std::string  default_ip = "",
int  default_port = StandardSocketPorts::MOTION 
)
virtual

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.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::init ( SmplMsgConnection connection)
virtual

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.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::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 in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 92 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::is_valid ( const trajectory_msgs::JointTrajectory &  traj)
protectedvirtual

Validate that trajectory command meets minimum requirements.

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

Definition at line 338 of file joint_trajectory_interface.cpp.

void industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::jointStateCB ( const sensor_msgs::JointStateConstPtr msg)
protectedvirtual

Definition at line 367 of file joint_trajectory_interface.cpp.

void industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::jointTrajectoryCB ( const trajectory_msgs::JointTrajectoryConstPtr &  msg)
protectedvirtual

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 in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 131 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::jointTrajectoryCB ( industrial_msgs::CmdJointTrajectory::Request &  req,
industrial_msgs::CmdJointTrajectory::Response &  res 
)
private

Callback function registered to ROS CmdJointTrajectory service Duplicates message-topic functionality, but in service form.

Parameters
reqCmdJointTrajectory request from service call
resCmdJointTrajectory response to service call
Returns
true always. Look at res.code.val to see if call actually succeeded

Definition at line 118 of file joint_trajectory_interface.cpp.

virtual void industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::run ( )
inlinevirtual

Begin processing messages and publishing topics.

Definition at line 116 of file joint_trajectory_interface.h.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::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 
)
protectedvirtual

Select specific joints for sending to the robot.

Parameters
[in]ros_joint_namesjoint names from ROS command
[in]ros_pttarget pos/vel from ROS command
[in]rbt_joint_namesjoint names, in order/count expected by robot connection
[out]rbt_pttarget pos/vel, matching rbt_joint_names
Returns
true on success, false otherwise

Definition at line 184 of file joint_trajectory_interface.cpp.

virtual bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::send_to_robot ( const std::vector< JointTrajPtMessage > &  messages)
protectedpure 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

Implemented in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer, and industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::stopMotionCB ( industrial_msgs::StopMotion::Request &  req,
industrial_msgs::StopMotion::Response &  res 
)
protectedvirtual

Callback function registered to ROS stopMotion service Sends stop-motion command to robot.

Parameters
reqStopMotion request from service call
resStopMotion response to service call
Returns
true always. Look at res.code.val to see if call actually succeeded.

Definition at line 327 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::trajectory_to_msgs ( const trajectory_msgs::JointTrajectoryConstPtr &  traj,
std::vector< JointTrajPtMessage > *  msgs 
)
protectedvirtual

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 in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 152 of file joint_trajectory_interface.cpp.

void industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::trajectoryStop ( )
protectedvirtual

Send a stop command to the robot.

Reimplemented in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 315 of file joint_trajectory_interface.cpp.

virtual bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::transform ( const trajectory_msgs::JointTrajectoryPoint &  pt_in,
trajectory_msgs::JointTrajectoryPoint *  pt_out 
)
inlineprotectedvirtual

Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling.

Parameters
[in]pt_intrajectory-point, in same order as expected for robot-connection.
[out]pt_outtransformed trajectory-point (in same order/count as input positions)
Returns
true on success, false otherwise

Definition at line 145 of file joint_trajectory_interface.h.

Member Data Documentation

std::vector<std::string> industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::all_joint_names_
protected

Definition at line 251 of file joint_trajectory_interface.h.

SmplMsgConnection* industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::connection_
protected

Definition at line 246 of file joint_trajectory_interface.h.

sensor_msgs::JointState industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::cur_joint_pos_
protected

Definition at line 256 of file joint_trajectory_interface.h.

double industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::default_duration_
protected

Definition at line 254 of file joint_trajectory_interface.h.

double industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::default_joint_pos_
protected

Definition at line 252 of file joint_trajectory_interface.h.

TcpClient industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::default_tcp_connection_
protected

Definition at line 243 of file joint_trajectory_interface.h.

double industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::default_vel_ratio_
protected

Definition at line 253 of file joint_trajectory_interface.h.

std::map<std::string, double> industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::joint_vel_limits_
protected

Definition at line 255 of file joint_trajectory_interface.h.

ros::NodeHandle industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::node_
protected

Definition at line 245 of file joint_trajectory_interface.h.

ros::ServiceServer industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::srv_joint_trajectory_
protected

Definition at line 249 of file joint_trajectory_interface.h.

ros::ServiceServer industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::srv_stop_motion_
protected

Definition at line 250 of file joint_trajectory_interface.h.

ros::Subscriber industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::sub_cur_pos_
protected

Definition at line 247 of file joint_trajectory_interface.h.

ros::Subscriber industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::sub_joint_trajectory_
protected

Definition at line 248 of file joint_trajectory_interface.h.


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


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Sat Sep 21 2019 03:30:13