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 #ifndef VIGIR_FOOTSTEP_PLANNING_STEP_PLAN_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_STEP_PLAN_H__
00031
00032 #include <ros/ros.h>
00033
00034 #include <tf/tf.h>
00035
00036 #include <boost/thread/shared_mutex.hpp>
00037
00038 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
00039
00040
00041
00042 namespace vigir_footstep_planning
00043 {
00048 class StepPlan
00049 {
00050 public:
00051 StepPlan(const msgs::StepPlan& step_plan);
00052 StepPlan();
00053
00054 StepPlan& operator=(const msgs::StepPlan& step_plan);
00055 StepPlan& operator+(const msgs::StepPlan& step_plan);
00056 StepPlan& operator|(const msgs::StepPlan& step_plan);
00057
00058 StepPlan& operator+(const msgs::Step& step);
00059 StepPlan& operator|(const msgs::Step& step);
00060 StepPlan& operator-(const msgs::Step& step);
00061
00062 void clear()
00063 {
00064 boost::unique_lock<boost::shared_mutex> lock(step_plan_mutex);
00065 _clear();
00066 }
00067 bool empty() const
00068 {
00069 boost::shared_lock<boost::shared_mutex> lock(step_plan_mutex);
00070 return _empty();
00071 }
00072 size_t size() const
00073 {
00074 boost::shared_lock<boost::shared_mutex> lock(step_plan_mutex);
00075 return _size();
00076 }
00077
00078 int getFirstStepIndex() const;
00079 int getLastStepIndex() const;
00080
00081 msgs::ErrorStatus insertStep(const msgs::Step& step);
00082 msgs::ErrorStatus updateStep(const msgs::Step& step);
00083
00084 bool hasStep(unsigned int step_index) const
00085 {
00086 boost::shared_lock<boost::shared_mutex> lock(step_plan_mutex);
00087 return _hasStep(step_index);
00088 }
00089
00090 static bool getStep(msgs::Step& step, const msgs::StepPlan& step_plan, unsigned int step_index);
00091 inline bool getStep(msgs::Step& step, unsigned int step_index) const
00092 {
00093 boost::shared_lock<boost::shared_mutex> lock(step_plan_mutex);
00094 return _getStep(step, step_index);
00095 }
00096
00097 bool getStepAt(msgs::Step& step, unsigned int position) const;
00098 bool getfirstStep(msgs::Step& step) const;
00099 bool getLastStep(msgs::Step& step) const;
00100
00101 bool popStep(msgs::Step& step);
00102 bool popStep();
00103
00104 void removeStep(unsigned int step_index);
00105 void removeStepAt(unsigned int position);
00106
00107 void removeSteps(unsigned int from_step_index, int to_step_index = -1);
00108
00114 msgs::ErrorStatus appendStepPlan(const msgs::StepPlan& step_plan);
00115
00122 msgs::ErrorStatus updateStepPlan(const msgs::StepPlan& step_plan);
00123
00135 msgs::ErrorStatus stitchStepPlan(const msgs::StepPlan& step_plan, int step_index = 0);
00136
00144 static tf::Transform getTransform(const geometry_msgs::Pose& current, const geometry_msgs::Pose& target);
00145 static void transformStepPlan(msgs::StepPlan& step_plan, const tf::Transform& transform);
00146
00147 msgs::ErrorStatus fromMsg(const msgs::StepPlan& step_plan);
00148 msgs::ErrorStatus toMsg(msgs::StepPlan& step_plan) const;
00149
00150
00151 typedef boost::shared_ptr<StepPlan> Ptr;
00152 typedef boost::shared_ptr<const StepPlan> ConstPtr;
00153
00154 protected:
00156 void _clear();
00157 bool _empty() const;
00158 size_t _size() const;
00159
00160 bool _hasStep(unsigned int step_index) const;
00161
00162 bool _getStep(msgs::Step& step, unsigned int step_index) const;
00163
00170 msgs::ErrorStatus _insertStep(const msgs::Step& step);
00171
00178 msgs::ErrorStatus _updateStep(const msgs::Step& step);
00179
00185 msgs::ErrorStatus _appendStepPlan(const msgs::StepPlan& step_plan);
00186
00193 msgs::ErrorStatus _updateStepPlan(const msgs::StepPlan& step_plan);
00194
00205 msgs::ErrorStatus _stitchStepPlan(const msgs::StepPlan& step_plan, int step_index = 0);
00206
00207 mutable boost::shared_mutex step_plan_mutex;
00208
00209 std_msgs::Header header;
00210 msgs::Feet start;
00211 msgs::Feet goal;
00212 std::map<unsigned int, msgs::Step> steps;
00213 uint8_t mode;
00214 std::vector<uint8_t> data;
00215 };
00216 }
00217
00218 #endif