#include <play_motion_server.h>
Public Member Functions | |
PlayMotionServer (const ros::NodeHandle &nh, const PlayMotionPtr &pm) | |
virtual | ~PlayMotionServer () |
Private Types | |
typedef actionlib::ActionServer < play_motion_msgs::PlayMotionAction > | AlServer |
typedef boost::shared_ptr < PlayMotion > | PlayMotionPtr |
Private Member Functions | |
void | alCancelCb (AlServer::GoalHandle gh) |
void | alGoalCb (AlServer::GoalHandle gh) |
bool | findGoalId (AlServer::GoalHandle gh, PlayMotion::GoalHandle &goal_id) |
bool | listMotions (play_motion_msgs::ListMotions::Request &req, play_motion_msgs::ListMotions::Response &resp) |
void | playMotionCb (const PlayMotion::GoalHandle &goal_hdl) |
Private Attributes | |
std::map < PlayMotion::GoalHandle, AlServer::GoalHandle > | al_goals_ |
AlServer | al_server_ |
std::vector< std::string > | clist_ |
ros::ServiceServer | list_motions_srv_ |
ros::NodeHandle | nh_ |
PlayMotionPtr | pm_ |
Definition at line 54 of file play_motion_server.h.
typedef actionlib::ActionServer<play_motion_msgs::PlayMotionAction> play_motion::PlayMotionServer::AlServer [private] |
Definition at line 57 of file play_motion_server.h.
typedef boost::shared_ptr<PlayMotion> play_motion::PlayMotionServer::PlayMotionPtr [private] |
Definition at line 58 of file play_motion_server.h.
play_motion::PlayMotionServer::PlayMotionServer | ( | const ros::NodeHandle & | nh, |
const PlayMotionPtr & | pm | ||
) |
Definition at line 49 of file play_motion_server.cpp.
play_motion::PlayMotionServer::~PlayMotionServer | ( | ) | [virtual] |
Definition at line 63 of file play_motion_server.cpp.
void play_motion::PlayMotionServer::alCancelCb | ( | AlServer::GoalHandle | gh | ) | [private] |
Definition at line 98 of file play_motion_server.cpp.
void play_motion::PlayMotionServer::alGoalCb | ( | AlServer::GoalHandle | gh | ) | [private] |
Definition at line 110 of file play_motion_server.cpp.
bool play_motion::PlayMotionServer::findGoalId | ( | AlServer::GoalHandle | gh, |
PlayMotion::GoalHandle & | goal_id | ||
) | [private] |
Definition at line 66 of file play_motion_server.cpp.
bool play_motion::PlayMotionServer::listMotions | ( | play_motion_msgs::ListMotions::Request & | req, |
play_motion_msgs::ListMotions::Response & | resp | ||
) | [private] |
Definition at line 133 of file play_motion_server.cpp.
void play_motion::PlayMotionServer::playMotionCb | ( | const PlayMotion::GoalHandle & | goal_hdl | ) | [private] |
Definition at line 76 of file play_motion_server.cpp.
std::map<PlayMotion::GoalHandle, AlServer::GoalHandle> play_motion::PlayMotionServer::al_goals_ [private] |
Definition at line 76 of file play_motion_server.h.
Definition at line 75 of file play_motion_server.h.
std::vector<std::string> play_motion::PlayMotionServer::clist_ [private] |
Definition at line 73 of file play_motion_server.h.
Definition at line 77 of file play_motion_server.h.
Definition at line 72 of file play_motion_server.h.
Definition at line 74 of file play_motion_server.h.