Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include "play_motion/play_motion_server.h"
00038
00039 #include <boost/foreach.hpp>
00040
00041 #include "play_motion/play_motion.h"
00042 #include "play_motion/play_motion_helpers.h"
00043 #include "play_motion/xmlrpc_helpers.h"
00044
00045 #define foreach BOOST_FOREACH
00046
00047 namespace play_motion
00048 {
00049 PlayMotionServer::PlayMotionServer(const ros::NodeHandle& nh, const PlayMotionPtr& pm) :
00050 nh_(nh),
00051 pm_(pm),
00052 al_server_(nh_, "play_motion", false)
00053 {
00054 al_server_.registerGoalCallback(boost::bind(&PlayMotionServer::alGoalCb, this, _1));
00055 al_server_.registerCancelCallback(boost::bind(&PlayMotionServer::alCancelCb, this, _1));
00056 al_server_.start();
00057
00058 list_motions_srv_ = ros::NodeHandle("~").advertiseService("list_motions",
00059 &PlayMotionServer::listMotions,
00060 this);
00061 }
00062
00063 PlayMotionServer::~PlayMotionServer()
00064 {}
00065
00066 bool PlayMotionServer::findGoalId(AlServer::GoalHandle gh, PlayMotion::GoalHandle& goal_hdl)
00067 {
00068 typedef std::pair<PlayMotion::GoalHandle, AlServer::GoalHandle> goal_pair_t;
00069 foreach (const goal_pair_t& p, al_goals_)
00070 if (goal_hdl = p.first, p.second == gh)
00071 return true;
00072
00073 return false;
00074 }
00075
00076 void PlayMotionServer::playMotionCb(const PlayMotion::GoalHandle& goal_hdl)
00077 {
00078 PMR r;
00079 r.error_code = goal_hdl->error_code;
00080 r.error_string = goal_hdl->error_string;
00081
00082 if (r.error_code == PMR::SUCCEEDED)
00083 {
00084 ROS_INFO("Motion played successfully.");
00085 al_goals_[goal_hdl].setSucceeded(r);
00086 }
00087 else
00088 {
00089 if (r.error_code == 0)
00090 ROS_ERROR("Motion ended with INVALID ERROR code %d and description '%s'", r.error_code, r.error_string.c_str());
00091 else
00092 ROS_WARN("Motion ended with an error code %d and description '%s'", r.error_code, r.error_string.c_str());
00093 al_goals_[goal_hdl].setAborted(r);
00094 }
00095 al_goals_.erase(goal_hdl);
00096 }
00097
00098 void PlayMotionServer::alCancelCb(AlServer::GoalHandle gh)
00099 {
00100 PlayMotion::GoalHandle goal_hdl;
00101 if (findGoalId(gh, goal_hdl))
00102 goal_hdl->cancel();
00103 else
00104 ROS_ERROR("Cancel request could not be fulfilled. Goal not running?.");
00105
00106 al_goals_.erase(goal_hdl);
00107 gh.setCanceled();
00108 }
00109
00110 void PlayMotionServer::alGoalCb(AlServer::GoalHandle gh)
00111 {
00112 AlServer::GoalConstPtr goal = gh.getGoal();
00113 ROS_INFO_STREAM("Received request to play motion '" << goal->motion_name << "'.");
00114 PlayMotion::GoalHandle goal_hdl;
00115 if (!pm_->run(goal->motion_name,
00116 goal->skip_planning,
00117 goal_hdl,
00118 boost::bind(&PlayMotionServer::playMotionCb, this, _1)))
00119 {
00120 PMR r;
00121 r.error_code = goal_hdl->error_code;
00122 r.error_string = goal_hdl->error_string;
00123 if (!r.error_string.empty())
00124 ROS_ERROR_STREAM(r.error_string);
00125 ROS_ERROR_STREAM("Motion '" << goal->motion_name << "' could not be played.");
00126 gh.setRejected(r);
00127 return;
00128 }
00129 gh.setAccepted();
00130 al_goals_[goal_hdl] = gh;
00131 }
00132
00133 bool PlayMotionServer::listMotions(play_motion_msgs::ListMotions::Request& req,
00134 play_motion_msgs::ListMotions::Response& resp)
00135 {
00136 try
00137 {
00138 MotionNames motions;
00139 ros::NodeHandle pnh("~");
00140 getMotionIds(pnh, motions);
00141 foreach (const std::string& motion, motions)
00142 {
00143 play_motion_msgs::MotionInfo info;
00144 info.name = motion;
00145 getMotionJoints(pnh, motion, info.joints);
00146 getMotionDuration(pnh, motion);
00147 resp.motions.push_back(info);
00148 }
00149 }
00150 catch (const xh::XmlrpcHelperException& e)
00151 {
00152 ROS_ERROR_STREAM(e.what());
00153 return false;
00154 }
00155 return true;
00156 }
00157 }