Public Member Functions | List of all members
industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader Class Reference

Message handler that downloads joint trajectories to a robot controller that supports the trajectory downloading interface. More...

#include <joint_trajectory_downloader.h>

Inheritance diagram for industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader:
Inheritance graph
[legend]

Public Member Functions

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

Additional Inherited Members

- 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 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 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 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 downloads joint trajectories to a robot controller that supports the trajectory downloading interface.

Definition at line 49 of file joint_trajectory_downloader.h.

Member Function Documentation

bool industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader::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 42 of file joint_trajectory_downloader.cpp.


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