footstep.h
Go to the documentation of this file.
00001 // SVN $HeadURL: https://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_navigation/footstep_planner/include/footstep_planner/Dstar.h $
00002 // SVN $Id: Dstar.h 1168 2011-03-30 03:18:02Z hornunga@informatik.uni-freiburg.de $
00003 
00004 /*
00005  * A footstep planner for humanoid robots
00006  *
00007  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
00008  * http://www.ros.org/wiki/footstep_planner
00009  *
00010  * D* Lite (Koenig et al. 2002) partly based on the implementation
00011  * by J. Neufeld (http://code.google.com/p/dstarlite/)
00012  *
00013  *
00014  * This program is free software: you can redistribute it and/or modify
00015  * it under the terms of the GNU General Public License as published by
00016  * the Free Software Foundation, version 3.
00017  *
00018  * This program is distributed in the hope that it will be useful,
00019  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00020  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00021  * GNU General Public License for more details.
00022  *
00023  * You should have received a copy of the GNU General Public License
00024  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00025  */
00026 
00027 #ifndef FOOTSTEP_PLANNER_FOOTSTEP_H_
00028 #define FOOTSTEP_PLANNER_FOOTSTEP_H_
00029 
00030 #include <vigir_footstep_planning_lib/modeling/planning_state.h>
00031 
00032 
00033 
00034 namespace vigir_footstep_planning
00035 {
00044 class Footstep
00045 {
00046 public:
00061   Footstep(double x, double y, double theta, double step_cost, double cell_size, int num_angle_bins, int max_hash_size);
00062   ~Footstep();
00063 
00072   PlanningState performMeOnThisState(const PlanningState& current) const;
00073 
00082   PlanningState reverseMeOnThisState(const PlanningState& current) const;
00083 
00084   double getStepCost() const { return ivStepCost; }
00085 
00086 private:
00088   typedef std::pair<int, int> footstep_xy;
00089 
00091   void init(double x, double y);
00092 
00110   int calculateForwardStep(Leg leg, int global_theta, double x, double y, int* footstep_x, int* footstep_y) const;
00111 
00113   double ivCellSize;
00115   int ivNumAngleBins;
00116   double ivAngleBinSize;
00117 
00119   int ivTheta;
00120 
00121   double ivStepCost;
00122 
00124   int ivMaxHashSize;
00125 
00127   std::vector<footstep_xy> ivDiscSuccessorLeft;
00129   std::vector<footstep_xy> ivDiscSuccessorRight;
00131   std::vector<footstep_xy> ivDiscPredecessorLeft;
00133   std::vector<footstep_xy> ivDiscPredecessorRight;
00134 };
00135 } // end of namespace
00136 
00137 #endif  // FOOTSTEP_PLANNER_FOOTSTEP_H_


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Sat Jul 15 2017 02:47:56