21
21
22
22
#include < cmath>
23
23
#include < iostream>
24
+ #include < limits>
24
25
25
26
namespace steering_odometry
26
27
{
@@ -128,13 +129,26 @@ bool SteeringOdometry::update_from_velocity(
128
129
return update_odometry (linear_velocity, angular_velocity, dt);
129
130
}
130
131
132
+ double SteeringOdometry::get_linear_velocity_double_traction_axle (
133
+ const double right_traction_wheel_vel, const double left_traction_wheel_vel,
134
+ const double steer_pos)
135
+ {
136
+ double turning_radius = wheelbase_ / std::tan (steer_pos);
137
+ // overdetermined, we take the average
138
+ double vel_r = right_traction_wheel_vel * wheel_radius_ * turning_radius /
139
+ (turning_radius + wheel_track_ * 0.5 );
140
+ double vel_l = left_traction_wheel_vel * wheel_radius_ * turning_radius /
141
+ (turning_radius - wheel_track_ * 0.5 );
142
+ return (vel_r + vel_l) * 0.5 ;
143
+ }
144
+
131
145
bool SteeringOdometry::update_from_velocity (
132
146
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
133
147
const double steer_pos, const double dt)
134
148
{
135
- double linear_velocity =
136
- (right_traction_wheel_vel + left_traction_wheel_vel) * wheel_radius_ * 0.5 ;
137
149
steer_pos_ = steer_pos;
150
+ double linear_velocity = get_linear_velocity_double_traction_axle (
151
+ right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_);
138
152
139
153
const double angular_velocity = std::tan (steer_pos_) * linear_velocity / wheelbase_;
140
154
@@ -145,10 +159,18 @@ bool SteeringOdometry::update_from_velocity(
145
159
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
146
160
const double right_steer_pos, const double left_steer_pos, const double dt)
147
161
{
148
- steer_pos_ = (right_steer_pos + left_steer_pos) * 0.5 ;
149
- double linear_velocity =
150
- (right_traction_wheel_vel + left_traction_wheel_vel) * wheel_radius_ * 0.5 ;
151
- const double angular_velocity = std::tan (steer_pos_) * linear_velocity / wheelbase_;
162
+ // overdetermined, we take the average
163
+ const double right_steer_pos_est = std::atan (
164
+ wheelbase_ * std::tan (right_steer_pos) /
165
+ (wheelbase_ - wheel_track_ / 2 * std::tan (right_steer_pos)));
166
+ const double left_steer_pos_est = std::atan (
167
+ wheelbase_ * std::tan (left_steer_pos) /
168
+ (wheelbase_ + wheel_track_ / 2 * std::tan (left_steer_pos)));
169
+ steer_pos_ = (right_steer_pos_est + left_steer_pos_est) * 0.5 ;
170
+
171
+ double linear_velocity = get_linear_velocity_double_traction_axle (
172
+ right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_);
173
+ const double angular_velocity = steer_pos_ * linear_velocity / wheelbase_;
152
174
153
175
return update_odometry (linear_velocity, angular_velocity, dt);
154
176
}
@@ -181,30 +203,41 @@ void SteeringOdometry::set_odometry_type(const unsigned int type) { config_type_
181
203
182
204
double SteeringOdometry::convert_twist_to_steering_angle (double v_bx, double omega_bz)
183
205
{
184
- if (omega_bz == 0 || v_bx == 0 )
206
+ if (fabs ( v_bx) < std::numeric_limits< float >:: epsilon () )
185
207
{
186
- return 0 ;
208
+ // avoid division by zero
209
+ return 0 .;
187
210
}
188
211
return std::atan (omega_bz * wheelbase_ / v_bx);
189
212
}
190
213
191
214
std::tuple<std::vector<double >, std::vector<double >> SteeringOdometry::get_commands (
192
- const double v_bx, const double omega_bz)
215
+ const double v_bx, const double omega_bz, const bool open_loop )
193
216
{
194
217
// desired wheel speed and steering angle of the middle of traction and steering axis
195
- double Ws, phi;
218
+ double Ws, phi, phi_IK = steer_pos_ ;
196
219
220
+ #if 0
197
221
if (v_bx == 0 && omega_bz != 0)
198
222
{
199
- // TODO(anyone) would be only valid if traction is on the steering axis -> tricycle_controller
223
+ // TODO(anyone) this would be only possible if traction is on the steering axis
200
224
phi = omega_bz > 0 ? M_PI_2 : -M_PI_2;
201
225
Ws = abs(omega_bz) * wheelbase_ / wheel_radius_;
202
226
}
203
227
else
204
228
{
205
- phi = SteeringOdometry::convert_twist_to_steering_angle (v_bx, omega_bz);
206
- Ws = v_bx / (wheel_radius_ * std::cos (steer_pos_));
229
+ // TODO(anyone) this would be valid only if traction is on the steering axis
230
+ Ws = v_bx / (wheel_radius_ * std::cos(phi_IK)); // using the measured steering angle
231
+ }
232
+ #endif
233
+ // steering angle
234
+ phi = SteeringOdometry::convert_twist_to_steering_angle (v_bx, omega_bz);
235
+ if (open_loop)
236
+ {
237
+ phi_IK = phi;
207
238
}
239
+ // wheel speed
240
+ Ws = v_bx / wheel_radius_;
208
241
209
242
if (config_type_ == BICYCLE_CONFIG)
210
243
{
@@ -216,32 +249,37 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
216
249
{
217
250
std::vector<double > traction_commands;
218
251
std::vector<double > steering_commands;
219
- if (fabs (steer_pos_) < 1e-6 )
252
+ // double-traction axle
253
+ if (is_close_to_zero (phi_IK))
220
254
{
255
+ // avoid division by zero
221
256
traction_commands = {Ws, Ws};
222
257
}
223
258
else
224
259
{
225
- const double turning_radius = wheelbase_ / std::tan (steer_pos_ );
260
+ const double turning_radius = wheelbase_ / std::tan (phi_IK );
226
261
const double Wr = Ws * (turning_radius + wheel_track_ * 0.5 ) / turning_radius;
227
262
const double Wl = Ws * (turning_radius - wheel_track_ * 0.5 ) / turning_radius;
228
263
traction_commands = {Wr, Wl};
229
264
}
265
+ // simple steering
230
266
steering_commands = {phi};
231
267
return std::make_tuple (traction_commands, steering_commands);
232
268
}
233
269
else if (config_type_ == ACKERMANN_CONFIG)
234
270
{
235
271
std::vector<double > traction_commands;
236
272
std::vector<double > steering_commands;
237
- if (fabs (steer_pos_) < 1e-6 )
273
+ if (is_close_to_zero (phi_IK) )
238
274
{
275
+ // avoid division by zero
239
276
traction_commands = {Ws, Ws};
277
+ // shortcut, no steering
240
278
steering_commands = {phi, phi};
241
279
}
242
280
else
243
281
{
244
- const double turning_radius = wheelbase_ / std::tan (steer_pos_ );
282
+ const double turning_radius = wheelbase_ / std::tan (phi_IK );
245
283
const double Wr = Ws * (turning_radius + wheel_track_ * 0.5 ) / turning_radius;
246
284
const double Wl = Ws * (turning_radius - wheel_track_ * 0.5 ) / turning_radius;
247
285
traction_commands = {Wr, Wl};
@@ -279,8 +317,8 @@ void SteeringOdometry::integrate_runge_kutta_2(
279
317
const double theta_mid = heading_ + omega_bz * 0.5 * dt;
280
318
281
319
// Use the intermediate values to update the state
282
- x_ += v_bx * cos (theta_mid) * dt;
283
- y_ += v_bx * sin (theta_mid) * dt;
320
+ x_ += v_bx * std:: cos (theta_mid) * dt;
321
+ y_ += v_bx * std:: sin (theta_mid) * dt;
284
322
heading_ += omega_bz * dt;
285
323
}
286
324
@@ -289,7 +327,7 @@ void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, co
289
327
const double delta_x_b = v_bx * dt;
290
328
const double delta_theta = omega_bz * dt;
291
329
292
- if (fabs (delta_theta) < 1e-6 )
330
+ if (is_close_to_zero (delta_theta))
293
331
{
294
332
// / Runge-Kutta 2nd Order (should solve problems when omega_bz is zero):
295
333
integrate_runge_kutta_2 (v_bx, omega_bz, dt);
@@ -300,8 +338,8 @@ void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, co
300
338
const double heading_old = heading_;
301
339
const double R = delta_x_b / delta_theta;
302
340
heading_ += delta_theta;
303
- x_ += R * (sin (heading_) - sin (heading_old));
304
- y_ += -R * (cos (heading_) - cos (heading_old));
341
+ x_ += R * (sin (heading_) - std:: sin (heading_old));
342
+ y_ += -R * (cos (heading_) - std:: cos (heading_old));
305
343
}
306
344
}
307
345
0 commit comments