Message handler that relays joint trajectories to the motoman controller. More...
#include <joint_trajectory_handler.h>
| Public Member Functions | |
| unsigned int | getNextTrajectoryPoint (const trajectory_msgs::JointTrajectory &traj, const ros::Time &start, const ros::Time &cur) | 
| void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg) | 
| JointTrajectoryHandler () | |
| JointTrajectoryHandler (ros::NodeHandle &n, industrial::smpl_msg_connection::SmplMsgConnection *robotConnecton) | |
| Constructor. | |
| void | trajectoryHandler () | 
| ~JointTrajectoryHandler () | |
| Private Member Functions | |
| void | trajectoryStop () | 
| Private Attributes | |
| trajectory_msgs::JointTrajectory | current_traj_ | 
| int | currentPoint | 
| boost::mutex | mutex_ | 
| ros::NodeHandle | node_ | 
| industrial::smpl_msg_connection::SmplMsgConnection * | robot_ | 
| JointTrajectoryState | state_ | 
| ros::Time | streaming_start_ | 
| ros::Subscriber | sub_joint_tranectory_ | 
| boost::thread * | trajectoryHandler_ | 
| Static Private Attributes | |
| static const int | NUM_OF_JOINTS_ = 7 | 
Message handler that relays joint trajectories to the motoman controller.
THIS CLASS IS NOT THREAD-SAFE
Definition at line 65 of file joint_trajectory_handler.h.
Definition at line 44 of file joint_trajectory_handler.cpp.
| motoman::joint_trajectory_handler::JointTrajectoryHandler::JointTrajectoryHandler | ( | ros::NodeHandle & | n, | 
| industrial::smpl_msg_connection::SmplMsgConnection * | robotConnecton | ||
| ) | 
Constructor.
| ROS | node handle (used for subscribing) | 
| ROS | node handle (used for publishing (to the robot controller)) | 
Definition at line 48 of file joint_trajectory_handler.cpp.
Definition at line 65 of file joint_trajectory_handler.cpp.
| unsigned int motoman::joint_trajectory_handler::JointTrajectoryHandler::getNextTrajectoryPoint | ( | const trajectory_msgs::JointTrajectory & | traj, | 
| const ros::Time & | start, | ||
| const ros::Time & | cur | ||
| ) | 
Definition at line 203 of file joint_trajectory_handler.cpp.
| void motoman::joint_trajectory_handler::JointTrajectoryHandler::jointTrajectoryCB | ( | const trajectory_msgs::JointTrajectoryConstPtr & | msg | ) | 
Definition at line 72 of file joint_trajectory_handler.cpp.
Definition at line 116 of file joint_trajectory_handler.cpp.
| void motoman::joint_trajectory_handler::JointTrajectoryHandler::trajectoryStop | ( | ) |  [private] | 
Definition at line 217 of file joint_trajectory_handler.cpp.
| trajectory_msgs::JointTrajectory motoman::joint_trajectory_handler::JointTrajectoryHandler::current_traj_  [private] | 
Definition at line 99 of file joint_trajectory_handler.h.
Definition at line 98 of file joint_trajectory_handler.h.
| boost::mutex motoman::joint_trajectory_handler::JointTrajectoryHandler::mutex_  [private] | 
Definition at line 98 of file joint_trajectory_handler.h.
Definition at line 95 of file joint_trajectory_handler.h.
| const int motoman::joint_trajectory_handler::JointTrajectoryHandler::NUM_OF_JOINTS_ = 7  [static, private] | 
Definition at line 103 of file joint_trajectory_handler.h.
| industrial::smpl_msg_connection::SmplMsgConnection* motoman::joint_trajectory_handler::JointTrajectoryHandler::robot_  [private] | 
Definition at line 93 of file joint_trajectory_handler.h.
Definition at line 100 of file joint_trajectory_handler.h.
Definition at line 101 of file joint_trajectory_handler.h.
| ros::Subscriber motoman::joint_trajectory_handler::JointTrajectoryHandler::sub_joint_tranectory_  [private] | 
Definition at line 94 of file joint_trajectory_handler.h.
| boost::thread* motoman::joint_trajectory_handler::JointTrajectoryHandler::trajectoryHandler_  [private] | 
Definition at line 97 of file joint_trajectory_handler.h.