play_motion.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2013, PAL Robotics, S.L.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of PAL Robotics, S.L. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00038 #ifndef REACHPOSE_H
00039 #define REACHPOSE_H
00040 
00041 #include <string>
00042 #include <list>
00043 #include <map>
00044 #include <ros/ros.h>
00045 #include <boost/foreach.hpp>
00046 
00047 #include "play_motion/datatypes.h"
00048 #include "play_motion/controller_updater.h"
00049 #include "play_motion_msgs/PlayMotionResult.h"
00050 
00051 namespace sensor_msgs
00052 { ROS_DECLARE_MESSAGE(JointState); }
00053 
00054 namespace play_motion
00055 {
00056   typedef play_motion_msgs::PlayMotionResult PMR;
00057 
00058   class MoveJointGroup;
00059   class ApproachPlanner;
00060 
00061   class PMException : public ros::Exception
00062   {
00063   public:
00064     PMException(const std::string& what, int error_code = PMR::OTHER_ERROR)
00065       : ros::Exception(what)
00066     { error_code_ = error_code; }
00067 
00068     int error_code() const
00069     { return error_code_; }
00070 
00071   private:
00072     int error_code_;
00073   };
00074 
00078   class PlayMotion
00079   {
00080   public:
00081     class Goal;
00082     typedef boost::shared_ptr<Goal> GoalHandle;
00083   private:
00084     typedef boost::shared_ptr<MoveJointGroup>        MoveJointGroupPtr;
00085     typedef std::list<MoveJointGroupPtr>             ControllerList;
00086     typedef boost::function<void(const GoalHandle&)> Callback;
00087     typedef boost::shared_ptr<ApproachPlanner>       ApproachPlannerPtr;
00088 
00089   public:
00090     class Goal
00091     {
00092       friend class PlayMotion;
00093 
00094     public:
00095       int            error_code;
00096       std::string    error_string;
00097       int            active_controllers;
00098       Callback       cb;
00099       ControllerList controllers;
00100       bool           canceled;
00101 
00102       ~Goal();
00103       void cancel();
00104       void addController(const MoveJointGroupPtr& ctrl);
00105 
00106     private:
00107       Goal(const Callback& cbk);
00108     };
00109 
00110     PlayMotion(ros::NodeHandle& nh);
00111 
00116     bool run(const std::string& motion_name,
00117              bool               skip_planning,
00118              GoalHandle&        gh,
00119              const Callback&    cb);
00120 
00121   private:
00122     void jointStateCb(const sensor_msgs::JointStatePtr& msg);
00123 
00124     bool getGroupTraj(MoveJointGroupPtr move_joint_group,
00125                       const JointNames& motion_joints,
00126                       const Trajectory& motion_points, Trajectory& traj_group);
00127     void getMotionJoints(const std::string& motion_name, JointNames& motion_joints);
00128     void getMotionPoints(const std::string& motion_name, Trajectory& motion_points);
00129 
00137     ControllerList getMotionControllers(const JointNames& motion_joints);
00138     void updateControllersCb(const ControllerUpdater::ControllerStates& states,
00139                              const ControllerUpdater::ControllerJoints& joints);
00140 
00141     ros::NodeHandle                  nh_;
00142     ControllerList                   move_joint_groups_;
00143     std::map<std::string, double>    joint_states_;
00144     ros::Subscriber                  joint_states_sub_;
00145     ControllerUpdater                ctrlr_updater_;
00146     ApproachPlannerPtr               approach_planner_;
00147   };
00148 }
00149 
00150 #endif


play_motion
Author(s): Paul Mathieu
autogenerated on Wed Aug 26 2015 15:29:25