Message handler that downloads joint trajectories to the motoman controller. More...
#include <joint_trajectory_downloader.h>
Public Member Functions | |
void | jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg) |
JointTrajectoryDownloader () | |
JointTrajectoryDownloader (ros::NodeHandle &n, industrial::smpl_msg_connection::SmplMsgConnection *robotConnecton) | |
Constructor. | |
~JointTrajectoryDownloader () | |
Private Member Functions | |
void | trajectoryStop () |
Private Attributes | |
ros::NodeHandle | node_ |
industrial::smpl_msg_connection::SmplMsgConnection * | robot_ |
ros::Subscriber | sub_joint_trajectory_ |
Message handler that downloads joint trajectories to the motoman controller.
THIS CLASS IS NOT THREAD-SAFE
Definition at line 55 of file joint_trajectory_downloader.h.
Definition at line 58 of file joint_trajectory_downloader.cpp.
motoman::joint_trajectory_downloader::JointTrajectoryDownloader::JointTrajectoryDownloader | ( | 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 62 of file joint_trajectory_downloader.cpp.
Definition at line 74 of file joint_trajectory_downloader.cpp.
void motoman::joint_trajectory_downloader::JointTrajectoryDownloader::jointTrajectoryCB | ( | const trajectory_msgs::JointTrajectoryConstPtr & | msg | ) |
Definition at line 80 of file joint_trajectory_downloader.cpp.
Definition at line 217 of file joint_trajectory_downloader.cpp.
Definition at line 78 of file joint_trajectory_downloader.h.
industrial::smpl_msg_connection::SmplMsgConnection* motoman::joint_trajectory_downloader::JointTrajectoryDownloader::robot_ [private] |
Definition at line 76 of file joint_trajectory_downloader.h.
ros::Subscriber motoman::joint_trajectory_downloader::JointTrajectoryDownloader::sub_joint_trajectory_ [private] |
Definition at line 77 of file joint_trajectory_downloader.h.