PlanningState.h
Go to the documentation of this file.
1 /*
2  * A footstep planner for humanoid robots
3  *
4  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
5  * http://www.ros.org/wiki/footstep_planner
6  *
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, version 3.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <http://www.gnu.org/licenses/>.
19  */
20 
21 #ifndef FOOTSTEP_PLANNER_PLANNINGSTATE_H_
22 #define FOOTSTEP_PLANNER_PLANNINGSTATE_H_
23 
25 #include <footstep_planner/State.h>
26 
27 
28 namespace footstep_planner
29 {
46 {
47 public:
59  PlanningState(double x, double y, double theta, Leg leg,
60  double cell_size, int num_angle_bins, int max_hash_size);
61 
66  PlanningState(int x, int y, int theta, Leg leg, int max_hash_size);
67 
69  PlanningState(const State& s, double cell_size, int num_angle_bins,
70  int max_hash_size);
71 
73  PlanningState(const PlanningState& s);
74 
76 
81  bool operator ==(const PlanningState& s2) const;
82 
87  bool operator !=(const PlanningState& s2) const;
88 
94  void setId(unsigned int id) { ivId = id; }
95 
96  Leg getLeg() const { return ivLeg; }
97  int getTheta() const { return ivTheta; }
98  int getX() const { return ivX; }
99  int getY() const { return ivY; }
100 
105  unsigned int getHashTag() const { return ivHashTag; }
106 
111  int getId() const { return ivId; }
112 
114  State getState(double cell_size, int num_angle_bins) const;
115 
116 private:
118  int ivX;
120  int ivY;
122  int ivTheta;
125 
127  int ivId;
128 
133  unsigned int ivHashTag;
134 };
135 }
136 #endif // FOOTSTEP_PLANNER_PLANNINGSTATE_H_
XmlRpcServer s
State getState(double cell_size, int num_angle_bins) const
Computes the continuous State the PlanningState represents.
void setId(unsigned int id)
Used to attach such an unique ID to the planning state. (This cannot be done in the constructor since...
Definition: PlanningState.h:94
bool operator!=(const PlanningState &s2) const
Compare two states on inequality of x, y, theta, leg by comparing the hash tags of the states...
A class representing the robot&#39;s pose (i.e. position and orientation) in the (continuous) world view...
Definition: State.h:34
PlanningState(double x, double y, double theta, Leg leg, double cell_size, int num_angle_bins, int max_hash_size)
x, y and theta represent the global (continuous) position and orientation of the robot&#39;s support leg...
int ivX
Value of the grid cell the position&#39;s x value is fitted into.
Leg ivLeg
The supporting leg.
int ivTheta
Number of the bin the orientation is fitted into.
int ivY
Value of the grid cell the position&#39;s y value is fitted into.
int ivId
The (unique) ID of the planning state.
unsigned int getHashTag() const
A class representing the robot&#39;s pose (i.e. position and orientation) in the underlying SBPL...
Definition: PlanningState.h:45
bool operator==(const PlanningState &s2) const
Compare two states on equality of x, y, theta, leg. Makes first use of the non-unique hash tag to rul...


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24