
Public Member Functions | |
| Fanuc_JointTrajectoryStreamer () | |
| bool | transform (const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out) |
| virtual | ~Fanuc_JointTrajectoryStreamer () |
Public Member Functions inherited from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer | |
| 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 >()) |
| virtual void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg) |
| JointTrajectoryStreamer (int min_buffer_size=1) | |
| bool | send_to_robot (const std::vector< JointTrajPtMessage > &messages) |
| void | streamingThread () |
| virtual bool | trajectory_to_msgs (const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs) |
| ~JointTrajectoryStreamer () | |
Public Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface | |
| virtual bool | init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION) |
| virtual bool | init (SmplMsgConnection *connection) |
| JointTrajectoryInterface () | |
| virtual void | run () |
| virtual | ~JointTrajectoryInterface () |
Private Attributes | |
| int | J23_factor_ |
Additional Inherited Members | |
Protected Member Functions inherited from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer | |
| void | trajectoryStop () |
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 | calc_velocity (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity) |
| virtual bool | is_valid (const trajectory_msgs::JointTrajectory &traj) |
| virtual void | jointStateCB (const sensor_msgs::JointStateConstPtr &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) |
Protected Attributes inherited from industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer | |
| int | current_point_ |
| std::vector< JointTrajPtMessage > | current_traj_ |
| int | min_buffer_size_ |
| boost::mutex | mutex_ |
| TransferState | state_ |
| ros::Time | streaming_start_ |
| boost::thread * | streaming_thread_ |
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 49 of file fanuc_joint_streamer_node.cpp.
|
inline |
Definition at line 55 of file fanuc_joint_streamer_node.cpp.
|
inlinevirtual |
Definition at line 67 of file fanuc_joint_streamer_node.cpp.
|
inlinevirtual |
Reimplemented from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface.
Definition at line 70 of file fanuc_joint_streamer_node.cpp.
|
private |
Definition at line 51 of file fanuc_joint_streamer_node.cpp.