$search
00001 // SVN $HeadURL: https://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_navigation/footstep_planner/src/Dstar.cpp $ 00002 // SVN $Id: Dstar.cpp 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 #include <footstep_planner/Footstep.h> 00028 00029 00030 namespace footstep_planner 00031 { 00032 Footstep::Footstep(double x, double y, double theta, double cell_size, 00033 int num_angle_bins, int max_hash_size) 00034 : ivTheta(angle_state_2_cell(theta, num_angle_bins)), 00035 ivContX(x), 00036 ivContY(y), 00037 ivCellSize(cell_size), 00038 ivNumAngleBins(num_angle_bins), 00039 ivMaxHashSize(max_hash_size), 00040 ivDiscSuccessorLeft(num_angle_bins), 00041 ivDiscSuccessorRight(num_angle_bins), 00042 ivDiscPredecessorLeft(num_angle_bins), 00043 ivDiscPredecessorRight(num_angle_bins) 00044 { 00045 init(); 00046 } 00047 00048 00049 Footstep::~Footstep() 00050 {} 00051 00052 00053 void 00054 Footstep::init() 00055 { 00056 int backward_angle; 00057 int footstep_x; 00058 int footstep_y; 00059 00060 for (int a = 0; a < ivNumAngleBins; ++a) 00061 { 00062 backward_angle = calculateForwardStep(RIGHT, a, &footstep_x, &footstep_y); 00063 ivDiscSuccessorRight[a] = footstep_xy(footstep_x, footstep_y); 00064 ivDiscPredecessorLeft[backward_angle] = footstep_xy(-footstep_x, 00065 -footstep_y); 00066 backward_angle = calculateForwardStep(LEFT, a, &footstep_x, &footstep_y); 00067 ivDiscSuccessorLeft[a] = footstep_xy(footstep_x, footstep_y); 00068 ivDiscPredecessorRight[backward_angle] = footstep_xy(-footstep_x, 00069 -footstep_y); 00070 } 00071 } 00072 00073 00074 PlanningState 00075 Footstep::performMeOnThisState(const PlanningState& current) 00076 const 00077 { 00078 Leg leg; 00079 00080 int x = current.getX(); 00081 int y = current.getY(); 00082 int theta = current.getTheta(); 00083 00084 if (current.getLeg() == RIGHT) 00085 { 00086 footstep_xy xy = ivDiscSuccessorRight[theta]; 00087 x += xy.first; 00088 y += xy.second; 00089 theta += ivTheta; 00090 leg = LEFT; 00091 } 00092 else // leg == LEFT 00093 { 00094 footstep_xy xy = ivDiscSuccessorLeft[theta]; 00095 x += xy.first; 00096 y += xy.second; 00097 theta -= ivTheta; 00098 leg = RIGHT; 00099 } 00100 00101 // theta has to be in [0..ivNumAngleBins) 00102 if (theta < 0) 00103 theta += ivNumAngleBins; 00104 else if (theta >= ivNumAngleBins) 00105 theta -= ivNumAngleBins; 00106 00107 return PlanningState(x, y, theta, leg, ivMaxHashSize); 00108 } 00109 00110 00111 PlanningState 00112 Footstep::reverseMeOnThisState(const PlanningState& current) 00113 const 00114 { 00115 Leg leg; 00116 00117 int x = current.getX(); 00118 int y = current.getY(); 00119 int theta = current.getTheta(); 00120 00121 if (current.getLeg() == LEFT) 00122 { 00123 footstep_xy xy = ivDiscPredecessorLeft[theta]; 00124 x += xy.first; 00125 y += xy.second; 00126 theta -= ivTheta; 00127 leg = RIGHT; 00128 } 00129 else // leg == RIGHT 00130 { 00131 footstep_xy xy = ivDiscPredecessorRight[theta]; 00132 x += xy.first; 00133 y += xy.second; 00134 theta += ivTheta; 00135 leg = LEFT; 00136 } 00137 // theta has to be in [0..ivNumAngleBins) 00138 if (theta < 0) 00139 theta += ivNumAngleBins; 00140 else if (theta >= ivNumAngleBins) 00141 theta -= ivNumAngleBins; 00142 00143 return PlanningState(x, y, theta, leg, ivMaxHashSize); 00144 } 00145 00146 00147 int 00148 Footstep::calculateForwardStep(Leg leg, int global_theta, 00149 int* footstep_x, int* footstep_y) 00150 const 00151 { 00152 double cont_footstep_x, cont_footstep_y; 00153 double cont_global_theta = angle_cell_2_state(global_theta, 00154 ivNumAngleBins); 00155 double theta_cos = cos(cont_global_theta); 00156 double theta_sin = sin(cont_global_theta); 00157 if (leg == RIGHT) 00158 { 00159 cont_footstep_x = theta_cos * ivContX - theta_sin * ivContY; 00160 cont_footstep_y = theta_sin * ivContX + theta_cos * ivContY; 00161 00162 global_theta += ivTheta; 00163 } 00164 else // leg == LEFT 00165 { 00166 cont_footstep_x = theta_cos * ivContX + theta_sin * ivContY; 00167 cont_footstep_y = theta_sin * ivContX - theta_cos * ivContY; 00168 00169 global_theta -= ivTheta; 00170 } 00171 *footstep_x = disc_val(cont_footstep_x, ivCellSize); 00172 *footstep_y = disc_val(cont_footstep_y, ivCellSize); 00173 00174 // theta has to be in [0..ivNumAngleBins) 00175 if (global_theta < 0) 00176 global_theta += ivNumAngleBins; 00177 else if (global_theta >= ivNumAngleBins) 00178 global_theta -= ivNumAngleBins; 00179 return global_theta; 00180 } 00181 } // end of namespace