Public Member Functions | |
bool | calc_velocity (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity) |
bool | init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION) |
bool | transform (const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out) |
Public Member Functions inherited from industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader | |
bool | send_to_robot (const std::vector< JointTrajPtMessage > &messages) |
Public Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface | |
virtual bool | init (SmplMsgConnection *connection) |
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 >()) |
JointTrajectoryInterface () | |
virtual void | run () |
virtual | ~JointTrajectoryInterface () |
Private Attributes | |
bool | J23_coupled_ |
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) |
virtual bool | calc_speed (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity, double *rbt_duration) |
virtual bool | is_valid (const trajectory_msgs::JointTrajectory &traj) |
virtual void | jointStateCB (const sensor_msgs::JointStateConstPtr &msg) |
virtual void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &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) |
virtual bool | stopMotionCB (industrial_msgs::StopMotion::Request &req, industrial_msgs::StopMotion::Response &res) |
virtual bool | trajectory_to_msgs (const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs) |
virtual void | trajectoryStop () |
Protected Attributes inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface | |
std::vector< std::string > | all_joint_names_ |
SmplMsgConnection * | connection_ |
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_ |
Definition at line 39 of file abb_joint_downloader_node.cpp.
|
inlinevirtual |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 68 of file abb_joint_downloader_node.cpp.
|
inlinevirtual |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 46 of file abb_joint_downloader_node.cpp.
|
inlinevirtual |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 59 of file abb_joint_downloader_node.cpp.
|
private |
Definition at line 43 of file abb_joint_downloader_node.cpp.