@@ -116,13 +116,59 @@ TEST(TestSteeringOdometry, ackermann_IK_right)
116116 odom.update_from_position (0 ., -0.2 , 1 .); // assume already turn
117117 auto cmd = odom.get_commands (1 ., -0.1 , false );
118118 auto cmd0 = std::get<0 >(cmd); // vel
119- EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left outer)
119+ EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left ( outer)
120120 EXPECT_GT (cmd0[0 ], 0 );
121121 auto cmd1 = std::get<1 >(cmd); // steer
122122 EXPECT_GT (std::abs (cmd1[0 ]), std::abs (cmd1[1 ])); // abs right (inner) > abs left (outer)
123123 EXPECT_LT (cmd1[0 ], 0 );
124124}
125125
126+ TEST (TestSteeringOdometry, ackermann_IK_right_steering_limited)
127+ {
128+ steering_odometry::SteeringOdometry odom (1 );
129+ odom.set_wheel_params (1 ., 2 ., 1 .);
130+ odom.set_odometry_type (steering_odometry::ACKERMANN_CONFIG);
131+
132+ {
133+ odom.update_from_position (0 ., -0.785 , 1 .); // already steered
134+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
135+ auto vel_cmd_steered = std::get<0 >(cmd); // vel
136+ EXPECT_LT (vel_cmd_steered[0 ], vel_cmd_steered[1 ]); // right (inner) < left (outer)
137+ EXPECT_GT (vel_cmd_steered[0 ], 0 );
138+ auto cmd1 = std::get<1 >(cmd); // steer
139+ EXPECT_GT (std::abs (cmd1[0 ]), std::abs (cmd1[1 ])); // abs right (inner) > abs left (outer)
140+ EXPECT_LT (cmd1[0 ], 0 );
141+ }
142+
143+ std::vector<double > vel_cmd_not_steered;
144+ {
145+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
146+ auto cmd = odom.get_commands (1 ., -0.5 , false , false );
147+ vel_cmd_not_steered = std::get<0 >(cmd); // vel
148+ EXPECT_LT (vel_cmd_not_steered[0 ], vel_cmd_not_steered[1 ]); // right (inner) < left (outer)
149+ EXPECT_GT (vel_cmd_not_steered[0 ], 0 );
150+ auto cmd1 = std::get<1 >(cmd); // steer
151+ EXPECT_GT (std::abs (cmd1[0 ]), std::abs (cmd1[1 ])); // abs right (inner) > abs left (outer)
152+ EXPECT_LT (cmd1[0 ], 0 );
153+ }
154+
155+ {
156+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
157+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
158+ auto cmd0 = std::get<0 >(cmd); // vel
159+ EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left (outer)
160+ EXPECT_GT (cmd0[0 ], 0 );
161+ // vel should be less than vel_cmd_not_steered now
162+ for (size_t i = 0 ; i < cmd0.size (); ++i)
163+ {
164+ EXPECT_LT (cmd0[i], vel_cmd_not_steered[i]);
165+ }
166+ auto cmd1 = std::get<1 >(cmd); // steer
167+ EXPECT_GT (std::abs (cmd1[0 ]), std::abs (cmd1[1 ])); // abs right (inner) > abs left (outer)
168+ EXPECT_LT (cmd1[0 ], 0 );
169+ }
170+ }
171+
126172// ----------------- bicycle -----------------
127173
128174TEST (TestSteeringOdometry, bicycle_IK_linear)
@@ -164,6 +210,62 @@ TEST(TestSteeringOdometry, bicycle_IK_right)
164210 EXPECT_LT (cmd1[0 ], 0 ); // left steering
165211}
166212
213+ TEST (TestSteeringOdometry, bicycle_IK_right_steering_limited)
214+ {
215+ steering_odometry::SteeringOdometry odom (1 );
216+ odom.set_wheel_params (1 ., 2 ., 1 .);
217+ odom.set_odometry_type (steering_odometry::BICYCLE_CONFIG);
218+
219+ {
220+ odom.update_from_position (0 ., -0.785 , 1 .); // already steered
221+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
222+ auto vel_cmd_steered = std::get<0 >(cmd); // vel
223+ EXPECT_DOUBLE_EQ (vel_cmd_steered[0 ], 1.0 ); // equals linear
224+ auto cmd1 = std::get<1 >(cmd); // steer
225+ EXPECT_LT (cmd1[0 ], 0 );
226+ }
227+
228+ std::vector<double > vel_cmd_not_steered;
229+ {
230+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
231+ auto cmd = odom.get_commands (1 ., -0.5 , false , false );
232+ vel_cmd_not_steered = std::get<0 >(cmd); // vel
233+ EXPECT_DOUBLE_EQ (vel_cmd_not_steered[0 ], 1.0 ); // equals linear
234+ auto cmd1 = std::get<1 >(cmd); // steer
235+ EXPECT_LT (cmd1[0 ], 0 );
236+ }
237+
238+ std::vector<double > vel_cmd_not_steered_limited;
239+ {
240+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
241+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
242+ vel_cmd_not_steered_limited = std::get<0 >(cmd); // vel
243+ EXPECT_GT (vel_cmd_not_steered_limited[0 ], 0 );
244+ // vel should be less than vel_cmd_not_steered now
245+ for (size_t i = 0 ; i < vel_cmd_not_steered_limited.size (); ++i)
246+ {
247+ EXPECT_LT (vel_cmd_not_steered_limited[i], vel_cmd_not_steered[i]);
248+ }
249+ auto cmd1 = std::get<1 >(cmd); // steer
250+ EXPECT_LT (cmd1[0 ], 0 );
251+ }
252+
253+ {
254+ // larger error -> check min of scale
255+ odom.update_from_position (0 ., M_PI, 1 .); // not fully steered
256+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
257+ auto cmd0 = std::get<0 >(cmd); // vel
258+ EXPECT_GT (cmd0[0 ], 0 );
259+ // vel should be less than vel_cmd_not_steered_limited now
260+ for (size_t i = 0 ; i < cmd0.size (); ++i)
261+ {
262+ EXPECT_LT (cmd0[i], vel_cmd_not_steered_limited[i]);
263+ }
264+ auto cmd1 = std::get<1 >(cmd); // steer
265+ EXPECT_LT (cmd1[0 ], 0 );
266+ }
267+ }
268+
167269TEST (TestSteeringOdometry, bicycle_odometry)
168270{
169271 steering_odometry::SteeringOdometry odom (1 );
@@ -214,12 +316,55 @@ TEST(TestSteeringOdometry, tricycle_IK_right)
214316 odom.update_from_position (0 ., -0.2 , 1 .); // assume already turn
215317 auto cmd = odom.get_commands (1 ., -0.1 , false );
216318 auto cmd0 = std::get<0 >(cmd); // vel
217- EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left outer)
319+ EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left ( outer)
218320 EXPECT_GT (cmd0[0 ], 0 );
219321 auto cmd1 = std::get<1 >(cmd); // steer
220322 EXPECT_LT (cmd1[0 ], 0 ); // right steering
221323}
222324
325+ TEST (TestSteeringOdometry, tricycle_IK_right_steering_limited)
326+ {
327+ steering_odometry::SteeringOdometry odom (1 );
328+ odom.set_wheel_params (1 ., 2 ., 1 .);
329+ odom.set_odometry_type (steering_odometry::TRICYCLE_CONFIG);
330+
331+ {
332+ odom.update_from_position (0 ., -0.785 , 1 .); // already steered
333+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
334+ auto vel_cmd_steered = std::get<0 >(cmd); // vel
335+ EXPECT_LT (vel_cmd_steered[0 ], vel_cmd_steered[1 ]); // right (inner) < left (outer)
336+ EXPECT_GT (vel_cmd_steered[0 ], 0 );
337+ auto cmd1 = std::get<1 >(cmd); // steer
338+ EXPECT_LT (cmd1[0 ], 0 );
339+ }
340+
341+ std::vector<double > vel_cmd_not_steered;
342+ {
343+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
344+ auto cmd = odom.get_commands (1 ., -0.5 , false , false );
345+ vel_cmd_not_steered = std::get<0 >(cmd); // vel
346+ EXPECT_LT (vel_cmd_not_steered[0 ], vel_cmd_not_steered[1 ]); // right (inner) < left (outer)
347+ EXPECT_GT (vel_cmd_not_steered[0 ], 0 );
348+ auto cmd1 = std::get<1 >(cmd); // steer
349+ EXPECT_LT (cmd1[0 ], 0 );
350+ }
351+
352+ {
353+ odom.update_from_position (0 ., -0.1 , 1 .); // not fully steered
354+ auto cmd = odom.get_commands (1 ., -0.5 , false , true );
355+ auto cmd0 = std::get<0 >(cmd); // vel
356+ EXPECT_LT (cmd0[0 ], cmd0[1 ]); // right (inner) < left (outer)
357+ EXPECT_GT (cmd0[0 ], 0 );
358+ // vel should be less than vel_cmd_not_steered now
359+ for (size_t i = 0 ; i < cmd0.size (); ++i)
360+ {
361+ EXPECT_LT (cmd0[i], vel_cmd_not_steered[i]);
362+ }
363+ auto cmd1 = std::get<1 >(cmd); // steer
364+ EXPECT_LT (cmd1[0 ], 0 );
365+ }
366+ }
367+
223368TEST (TestSteeringOdometry, tricycle_odometry)
224369{
225370 steering_odometry::SteeringOdometry odom (1 );
0 commit comments