32 #ifndef JOINT_TRAJECTORY_INTERFACE_H 33 #define JOINT_TRAJECTORY_INTERFACE_H 40 #include "industrial_msgs/CmdJointTrajectory.h" 41 #include "industrial_msgs/StopMotion.h" 42 #include "sensor_msgs/JointState.h" 46 #include "trajectory_msgs/JointTrajectory.h" 50 namespace joint_trajectory_interface
84 virtual bool init(std::string default_ip =
"",
int default_port = StandardSocketPorts::MOTION);
109 const std::map<std::string, double> &velocity_limits = std::map<std::string, double>());
134 virtual bool trajectory_to_msgs(
const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<JointTrajPtMessage>* msgs);
145 virtual bool transform(
const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
161 virtual bool select(
const std::vector<std::string>& ros_joint_names,
const trajectory_msgs::JointTrajectoryPoint& ros_pt,
162 const std::vector<std::string>& rbt_joint_names, trajectory_msgs::JointTrajectoryPoint* rbt_pt);
175 virtual bool calc_speed(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_velocity,
double* rbt_duration);
186 virtual bool calc_velocity(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_velocity);
197 virtual bool calc_duration(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_duration);
207 virtual bool send_to_robot(
const std::vector<JointTrajPtMessage>& messages)=0;
215 virtual void jointTrajectoryCB(
const trajectory_msgs::JointTrajectoryConstPtr &msg);
225 virtual bool stopMotionCB(industrial_msgs::StopMotion::Request &req,
226 industrial_msgs::StopMotion::Response &res);
234 virtual bool is_valid(
const trajectory_msgs::JointTrajectory &traj);
241 virtual void jointStateCB(
const sensor_msgs::JointStateConstPtr &msg);
271 industrial_msgs::CmdJointTrajectory::Response &res);
ros::Subscriber sub_cur_pos_
virtual void run()
Begin processing messages and publishing topics.
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 r...
ros::ServiceServer srv_joint_trajectory_
std::vector< std::string > all_joint_names_
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 join...
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...
SmplMsgConnection * connection_
sensor_msgs::JointState cur_joint_pos_
Message handler that relays joint trajectories to the robot controller.
ros::ServiceServer srv_stop_motion_
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 ...
ROSCPP_DECL void spin(Spinner &spinner)
double default_joint_pos_
static JointTrajPtMessage create_message(int seq, std::vector< double > joint_pos, double velocity, double duration)
double default_vel_ratio_
virtual void jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
Callback function registered to ROS topic-subscribe. Transform message into SimpleMessage objects and...
virtual bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
Initialize robot connection using default method.
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 void jointStateCB(const sensor_msgs::JointStateConstPtr &msg)
std::map< std::string, double > joint_vel_limits_
virtual bool is_valid(const trajectory_msgs::JointTrajectory &traj)
Validate that trajectory command meets minimum requirements.
virtual void trajectoryStop()
Send a stop command to the robot.
ros::Subscriber sub_joint_trajectory_
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 r...
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 ~JointTrajectoryInterface()
JointTrajectoryInterface()
Default constructor.
TcpClient default_tcp_connection_
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.