Main Page
Namespaces
Classes
Files
File List
File Members
include
footstep_planner
Footstep.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
*
9
* This program is free software: you can redistribute it and/or modify
10
* it under the terms of the GNU General Public License as published by
11
* the Free Software Foundation, version 3.
12
*
13
* This program is distributed in the hope that it will be useful,
14
* but WITHOUT ANY WARRANTY; without even the implied warranty of
15
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16
* GNU General Public License for more details.
17
*
18
* You should have received a copy of the GNU General Public License
19
* along with this program. If not, see <http://www.gnu.org/licenses/>.
20
*/
21
22
#ifndef FOOTSTEP_PLANNER_FOOTSTEP_H_
23
#define FOOTSTEP_PLANNER_FOOTSTEP_H_
24
25
#include <
footstep_planner/PlanningState.h
>
26
27
28
namespace
footstep_planner
29
{
38
class
Footstep
39
{
40
public
:
55
Footstep
(
double
x,
double
y,
double
theta
,
56
double
cell_size,
int
num_angle_bins,
int
max_hash_size);
57
~Footstep
();
58
67
PlanningState
performMeOnThisState
(
const
PlanningState
& current)
const
;
68
77
PlanningState
reverseMeOnThisState
(
const
PlanningState
& current)
const
;
78
79
private
:
81
typedef
std::pair<int, int>
footstep_xy
;
82
84
void
init
(
double
x,
double
y);
85
103
int
calculateForwardStep
(
Leg
leg,
int
global_theta,
104
double
x,
double
y,
105
int
* footstep_x,
int
* footstep_y)
const
;
106
108
int
ivTheta
;
109
111
double
ivCellSize
;
113
int
ivNumAngleBins
;
114
116
int
ivMaxHashSize
;
117
119
std::vector<footstep_xy>
ivDiscSuccessorLeft
;
121
std::vector<footstep_xy>
ivDiscSuccessorRight
;
123
std::vector<footstep_xy>
ivDiscPredecessorLeft
;
125
std::vector<footstep_xy>
ivDiscPredecessorRight
;
126
};
127
}
// end of namespace
128
129
#endif // FOOTSTEP_PLANNER_FOOTSTEP_H_
footstep_planner::Leg
Leg
Definition:
helper.h:41
footstep_planner::Footstep::reverseMeOnThisState
PlanningState reverseMeOnThisState(const PlanningState ¤t) const
Reverse this footstep on a given planning state.
Definition:
Footstep.cpp:106
footstep_planner::Footstep::init
void init(double x, double y)
Initialization method called within the constructor.
Definition:
Footstep.cpp:46
footstep_planner::Footstep::calculateForwardStep
int calculateForwardStep(Leg leg, int global_theta, double x, double y, int *footstep_x, int *footstep_y) const
Discretizes the translation of the footstep for a certain (discretized) orientation of a possible sta...
Definition:
Footstep.cpp:142
footstep_planner::Footstep::ivNumAngleBins
int ivNumAngleBins
The parameter for the discretization of the rotation.
Definition:
Footstep.h:113
footstep_planner::Footstep::performMeOnThisState
PlanningState performMeOnThisState(const PlanningState ¤t) const
Performs this footstep (translation and rotation) on a given planning state.
Definition:
Footstep.cpp:69
plan_footsteps.theta
theta
Definition:
plan_footsteps.py:38
PlanningState.h
footstep_planner::Footstep::Footstep
Footstep(double x, double y, double theta, double cell_size, int num_angle_bins, int max_hash_size)
The constructor takes the continuous translation and rotation of the footstep and calculates the resp...
Definition:
Footstep.cpp:26
footstep_planner::Footstep::ivDiscPredecessorRight
std::vector< footstep_xy > ivDiscPredecessorRight
The reversed (discretized) translation(s) for a right supporting foot.
Definition:
Footstep.h:125
footstep_planner::Footstep::ivTheta
int ivTheta
The (discretized) rotation of the footstep.
Definition:
Footstep.h:108
footstep_planner::Footstep::ivCellSize
double ivCellSize
The parameter for the discretization of the translation.
Definition:
Footstep.h:111
footstep_planner::Footstep::~Footstep
~Footstep()
Definition:
Footstep.cpp:41
footstep_planner::Footstep::ivDiscSuccessorRight
std::vector< footstep_xy > ivDiscSuccessorRight
The (discretized) translation(s) for a right supporting foot.
Definition:
Footstep.h:121
footstep_planner::Footstep
A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to t...
Definition:
Footstep.h:38
footstep_planner::Footstep::footstep_xy
std::pair< int, int > footstep_xy
Typedef representing the (discretized) translation of the footstep.
Definition:
Footstep.h:81
footstep_planner::PlanningState
A class representing the robot's pose (i.e. position and orientation) in the underlying SBPL...
Definition:
PlanningState.h:45
footstep_planner::Footstep::ivMaxHashSize
int ivMaxHashSize
The maximal hash size.
Definition:
Footstep.h:116
footstep_planner::Footstep::ivDiscPredecessorLeft
std::vector< footstep_xy > ivDiscPredecessorLeft
The reversed (discretized) translation(s) for a left supporting foot.
Definition:
Footstep.h:123
footstep_planner::Footstep::ivDiscSuccessorLeft
std::vector< footstep_xy > ivDiscSuccessorLeft
The (discretized) translation(s) for a left supporting foot.
Definition:
Footstep.h:119
footstep_planner
Definition:
Footstep.h:28
footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24