Footstep.cpp
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 
22 
23 
24 namespace footstep_planner
25 {
26 Footstep::Footstep(double x, double y, double theta, double cell_size,
27  int num_angle_bins, int max_hash_size)
28 : ivTheta(angle_state_2_cell(theta, num_angle_bins)),
29  ivCellSize(cell_size),
30  ivNumAngleBins(num_angle_bins),
31  ivMaxHashSize(max_hash_size),
32  ivDiscSuccessorLeft(num_angle_bins),
33  ivDiscSuccessorRight(num_angle_bins),
34  ivDiscPredecessorLeft(num_angle_bins),
35  ivDiscPredecessorRight(num_angle_bins)
36 {
37  init(x, y);
38 }
39 
40 
42 {}
43 
44 
45 void
46 Footstep::init(double x, double y)
47 {
48  int backward_angle;
49  int footstep_x;
50  int footstep_y;
51 
52  for (int a = 0; a < ivNumAngleBins; ++a)
53  {
54  backward_angle = calculateForwardStep(RIGHT, a, x, y,
55  &footstep_x, &footstep_y);
56  ivDiscSuccessorRight[a] = footstep_xy(footstep_x, footstep_y);
57  ivDiscPredecessorLeft[backward_angle] = footstep_xy(-footstep_x,
58  -footstep_y);
59  backward_angle = calculateForwardStep(LEFT, a, x, y,
60  &footstep_x, &footstep_y);
61  ivDiscSuccessorLeft[a] = footstep_xy(footstep_x, footstep_y);
62  ivDiscPredecessorRight[backward_angle] = footstep_xy(-footstep_x,
63  -footstep_y);
64  }
65 }
66 
67 
70 const
71 {
72  Leg leg;
73 
74  int x = current.getX();
75  int y = current.getY();
76  int theta = current.getTheta();
77 
78  if (current.getLeg() == RIGHT)
79  {
81  x += xy.first;
82  y += xy.second;
83  theta += ivTheta;
84  leg = LEFT;
85  }
86  else // leg == LEFT
87  {
89  x += xy.first;
90  y += xy.second;
91  theta -= ivTheta;
92  leg = RIGHT;
93  }
94 
95  // theta has to be in [0..ivNumAngleBins)
96  if (theta < 0)
97  theta += ivNumAngleBins;
98  else if (theta >= ivNumAngleBins)
99  theta -= ivNumAngleBins;
100 
101  return PlanningState(x, y, theta, leg, ivMaxHashSize);
102 }
103 
104 
107 const
108 {
109  Leg leg;
110 
111  int x = current.getX();
112  int y = current.getY();
113  int theta = current.getTheta();
114 
115  if (current.getLeg() == LEFT)
116  {
118  x += xy.first;
119  y += xy.second;
120  theta -= ivTheta;
121  leg = RIGHT;
122  }
123  else // leg == RIGHT
124  {
126  x += xy.first;
127  y += xy.second;
128  theta += ivTheta;
129  leg = LEFT;
130  }
131  // theta has to be in [0..ivNumAngleBins)
132  if (theta < 0)
133  theta += ivNumAngleBins;
134  else if (theta >= ivNumAngleBins)
135  theta -= ivNumAngleBins;
136 
137  return PlanningState(x, y, theta, leg, ivMaxHashSize);
138 }
139 
140 
141 int
142 Footstep::calculateForwardStep(Leg leg, int global_theta,
143  double x, double y,
144  int* footstep_x, int* footstep_y)
145 const
146 {
147  double cont_footstep_x, cont_footstep_y;
148  double cont_global_theta = angle_cell_2_state(global_theta,
150  double theta_cos = cos(cont_global_theta);
151  double theta_sin = sin(cont_global_theta);
152  if (leg == RIGHT)
153  {
154  cont_footstep_x = theta_cos * x - theta_sin * y;
155  cont_footstep_y = theta_sin * x + theta_cos * y;
156 
157  global_theta += ivTheta;
158  }
159  else // leg == LEFT
160  {
161  cont_footstep_x = theta_cos * x + theta_sin * y;
162  cont_footstep_y = theta_sin * x - theta_cos * y;
163 
164  global_theta -= ivTheta;
165  }
166  *footstep_x = disc_val(cont_footstep_x, ivCellSize);
167  *footstep_y = disc_val(cont_footstep_y, ivCellSize);
168 
169  // theta has to be in [0..ivNumAngleBins)
170  if (global_theta < 0)
171  global_theta += ivNumAngleBins;
172  else if (global_theta >= ivNumAngleBins)
173  global_theta -= ivNumAngleBins;
174  return global_theta;
175 }
176 } // end of namespace
PlanningState reverseMeOnThisState(const PlanningState &current) const
Reverse this footstep on a given planning state.
Definition: Footstep.cpp:106
void init(double x, double y)
Initialization method called within the constructor.
Definition: Footstep.cpp:46
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
int ivNumAngleBins
The parameter for the discretization of the rotation.
Definition: Footstep.h:113
int disc_val(double length, double cell_size)
Discretize a (continuous) value into cell size.
Definition: helper.h:130
double angle_cell_2_state(int angle, int angle_bin_num)
Calculate the respective (continuous) angle for a bin.
Definition: helper.h:101
PlanningState performMeOnThisState(const PlanningState &current) const
Performs this footstep (translation and rotation) on a given planning state.
Definition: Footstep.cpp:69
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
std::vector< footstep_xy > ivDiscPredecessorRight
The reversed (discretized) translation(s) for a right supporting foot.
Definition: Footstep.h:125
int ivTheta
The (discretized) rotation of the footstep.
Definition: Footstep.h:108
int angle_state_2_cell(double angle, int angle_bin_num)
Discretize a (continuous) angle into a bin.
Definition: helper.h:92
double ivCellSize
The parameter for the discretization of the translation.
Definition: Footstep.h:111
std::vector< footstep_xy > ivDiscSuccessorRight
The (discretized) translation(s) for a right supporting foot.
Definition: Footstep.h:121
std::pair< int, int > footstep_xy
Typedef representing the (discretized) translation of the footstep.
Definition: Footstep.h:81
A class representing the robot&#39;s pose (i.e. position and orientation) in the underlying SBPL...
Definition: PlanningState.h:45
int ivMaxHashSize
The maximal hash size.
Definition: Footstep.h:116
std::vector< footstep_xy > ivDiscPredecessorLeft
The reversed (discretized) translation(s) for a left supporting foot.
Definition: Footstep.h:123
std::vector< footstep_xy > ivDiscSuccessorLeft
The (discretized) translation(s) for a left supporting foot.
Definition: Footstep.h:119


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