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
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