Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions
industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface Class Reference

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]

List of all members.

Public Member Functions

virtual bool init ()
 Initialize robot connection using default method.
virtual bool init (SmplMsgConnection *connection)
 Initialize robot connection using specified method.
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.
 JointTrajectoryInterface ()
 Default constructor.
virtual void run ()
 Begin processing messages and publishing topics.
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).
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.
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).
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.
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.
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.)
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.
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.
virtual void trajectoryStop ()
 Send a stop command to the robot.
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.

Protected Attributes

std::vector< std::string > all_joint_names_
SmplMsgConnectionconnection_
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_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.

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 62 of file joint_trajectory_interface.h.


Constructor & Destructor Documentation

Default constructor.

Definition at line 70 of file joint_trajectory_interface.h.

Definition at line 92 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 
) [protected, virtual]

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 267 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 
) [protected, virtual]

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 200 of file joint_trajectory_interface.cpp.

bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::calc_velocity ( const trajectory_msgs::JointTrajectoryPoint &  pt,
double *  rbt_velocity 
) [protected, virtual]

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 211 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 
) [static, private]

Definition at line 283 of file joint_trajectory_interface.cpp.

Initialize robot connection using default method.

Returns:
true on success, false otherwise

Definition at line 49 of file joint_trajectory_interface.cpp.

Initialize robot connection using specified method.

Parameters:
connectionnew robot-connection instance (ALREADY INITIALIZED).
Returns:
true on success, false otherwise

Definition at line 68 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 77 of file joint_trajectory_interface.cpp.

void industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::jointTrajectoryCB ( const trajectory_msgs::JointTrajectoryConstPtr &  msg) [protected, 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 in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 111 of file joint_trajectory_interface.cpp.

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 98 of file joint_trajectory_interface.cpp.

Begin processing messages and publishing topics.

Definition at line 108 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 
) [protected, virtual]

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 160 of file joint_trajectory_interface.cpp.

virtual bool industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::send_to_robot ( const std::vector< JointTrajPtMessage > &  messages) [protected, pure 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.

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 312 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 
) [protected, 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 in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 132 of file joint_trajectory_interface.cpp.

Send a stop command to the robot.

Reimplemented in industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer.

Definition at line 300 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 
) [inline, protected, virtual]

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 137 of file joint_trajectory_interface.h.


Member Data Documentation

Definition at line 227 of file joint_trajectory_interface.h.

Definition at line 223 of file joint_trajectory_interface.h.

Definition at line 230 of file joint_trajectory_interface.h.

Definition at line 228 of file joint_trajectory_interface.h.

Definition at line 220 of file joint_trajectory_interface.h.

Definition at line 229 of file joint_trajectory_interface.h.

Definition at line 231 of file joint_trajectory_interface.h.

Definition at line 222 of file joint_trajectory_interface.h.

Definition at line 225 of file joint_trajectory_interface.h.

Definition at line 226 of file joint_trajectory_interface.h.

Definition at line 224 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 Mon Oct 6 2014 00:55:19