Skip to content

Commit a2c0e23

Browse files
committed
pybricks.robotics.DriveBase: Implement x/y motion.
1 parent 9f4f46c commit a2c0e23

2 files changed

Lines changed: 76 additions & 2 deletions

File tree

CHANGELOG.md

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,10 @@
55
## [Unreleased]
66

77
### Added
8-
- Added support for absolute turns with and without the gyro.
8+
- Added support for absolute turns with and without the gyro
9+
with `drive_base.turn(angle, absolute=True)` ([pybricks-micropython#458]).
10+
- Added support for coordinate traversals with `drive_base.move_by(dx, dy)` for
11+
practical navigation ([pybricks-micropython#458]).
912

1013
### Changed
1114
- Reset IMU heading to `0.0` at the start of a user program for consistent
@@ -17,6 +20,7 @@
1720

1821
[pybricks-micropython#454]: https://github.com/pybricks/pybricks-micropython/pull/454
1922
[pybricks-micropython#456]: https://github.com/pybricks/pybricks-micropython/pull/456
23+
[pybricks-micropython#458]: https://github.com/pybricks/pybricks-micropython/pull/458
2024

2125
## [4.0.0b4] - 2026-01-22
2226

pybricks/robotics/pb_type_drivebase.c

Lines changed: 71 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include <stdlib.h>
1010

1111
#include <pbio/drivebase.h>
12+
#include <pbio/geometry.h>
1213
#include <pbio/int_math.h>
1314

1415
#include "py/mphal.h"
@@ -34,6 +35,12 @@ struct _pb_type_DriveBase_obj_t {
3435
mp_obj_t distance_control;
3536
#endif
3637
pb_type_async_t *last_awaitable;
38+
/**
39+
* The move_by method is a sequence of a turn and a straight, so we
40+
* need to cache the arguments for the straight.
41+
*/
42+
int32_t secondary_distance;
43+
pbio_control_on_completion_t secondary_completion;
3744
};
3845

3946
// pybricks.robotics.DriveBase.reset
@@ -156,7 +163,6 @@ static mp_obj_t pb_type_DriveBase_turn(size_t n_args, const mp_obj_t *pos_args,
156163
mp_int_t angle = pb_obj_get_int(angle_in);
157164
pbio_control_on_completion_t then = pb_type_enum_get_value(then_in, &pb_enum_type_Stop);
158165

159-
// Turning in place is done as a curve with zero radius and a given angle.
160166
pb_assert(pbio_drivebase_drive_turn(self->db, angle, mp_obj_is_true(absolute_in), then));
161167

162168
// Old way to do parallel movement is to start and not wait on anything.
@@ -168,6 +174,67 @@ static mp_obj_t pb_type_DriveBase_turn(size_t n_args, const mp_obj_t *pos_args,
168174
}
169175
static MP_DEFINE_CONST_FUN_OBJ_KW(pb_type_DriveBase_turn_obj, 1, pb_type_DriveBase_turn);
170176

177+
#if MICROPY_PY_BUILTINS_FLOAT
178+
static pbio_error_t pb_type_drivebase_move_by_iterate_once(pbio_os_state_t *state, mp_obj_t parent_obj) {
179+
pb_type_DriveBase_obj_t *self = MP_OBJ_TO_PTR(parent_obj);
180+
181+
// Handle I/O exceptions like port unplugged.
182+
if (!pbio_drivebase_update_loop_is_running(self->db)) {
183+
pb_assert(PBIO_ERROR_NO_DEV);
184+
}
185+
186+
PBIO_OS_ASYNC_BEGIN(state);
187+
188+
// Turn has already been started. Await that first.
189+
PBIO_OS_AWAIT_UNTIL(state, pbio_drivebase_is_done(self->db));
190+
191+
// Use the cached arguments to start the straight.
192+
pbio_error_t err = pbio_drivebase_drive_straight(self->db, self->secondary_distance, self->secondary_completion);
193+
if (err != PBIO_SUCCESS) {
194+
return err;
195+
}
196+
197+
// Now await the straight move.
198+
PBIO_OS_AWAIT_UNTIL(state, pbio_drivebase_is_done(self->db));
199+
200+
PBIO_OS_ASYNC_END(PBIO_SUCCESS);
201+
}
202+
203+
// pybricks.robotics.DriveBase.move_by
204+
static mp_obj_t pb_type_DriveBase_move_by(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
205+
PB_PARSE_ARGS_METHOD(n_args, pos_args, kw_args,
206+
pb_type_DriveBase_obj_t, self,
207+
PB_ARG_REQUIRED(dx),
208+
PB_ARG_REQUIRED(dy),
209+
PB_ARG_DEFAULT_OBJ(then, pb_Stop_HOLD_obj));
210+
211+
int32_t dx = pb_obj_get_int(dx_in);
212+
int32_t dy = pb_obj_get_int(dy_in);
213+
214+
int32_t direction = (int32_t)pbio_geometry_radians_to_degrees(atan2f(dy, dx));
215+
216+
// Can't overflow the square root argument.
217+
if (pbio_int_math_max(pbio_int_math_abs(dx), pbio_int_math_abs(dy)) > INT16_MAX) {
218+
pb_assert(PBIO_ERROR_INVALID_ARG);
219+
}
220+
221+
// Turn towards the required heading.
222+
pb_assert(pbio_drivebase_drive_turn(self->db, -direction, true, PBIO_CONTROL_ON_COMPLETION_HOLD));
223+
224+
self->secondary_distance = (int32_t)sqrtf(dx * dx + dy * dy);
225+
self->secondary_completion = pb_type_enum_get_value(then_in, &pb_enum_type_Stop);
226+
227+
pb_type_async_t config = {
228+
.parent_obj = MP_OBJ_FROM_PTR(self),
229+
.iter_once = pb_type_drivebase_move_by_iterate_once,
230+
.close = pb_type_DriveBase_stop,
231+
};
232+
// New operation always wins; ongoing awaitable motion is cancelled.
233+
return pb_type_async_wait_or_await(&config, &self->last_awaitable, true);
234+
}
235+
static MP_DEFINE_CONST_FUN_OBJ_KW(pb_type_DriveBase_move_by_obj, 1, pb_type_DriveBase_move_by);
236+
#endif // MICROPY_PY_BUILTINS_FLOAT
237+
171238
// pybricks.robotics.DriveBase.curve
172239
static mp_obj_t pb_type_DriveBase_curve(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
173240
PB_PARSE_ARGS_METHOD(n_args, pos_args, kw_args,
@@ -410,6 +477,9 @@ static const mp_rom_map_elem_t pb_type_DriveBase_locals_dict_table[] = {
410477
#if PYBRICKS_PY_ROBOTICS_DRIVEBASE_GYRO
411478
{ MP_ROM_QSTR(MP_QSTR_use_gyro), MP_ROM_PTR(&pb_type_DriveBase_use_gyro_obj) },
412479
#endif
480+
#if MICROPY_PY_BUILTINS_FLOAT
481+
{ MP_ROM_QSTR(MP_QSTR_move_by), MP_ROM_PTR(&pb_type_DriveBase_move_by_obj) },
482+
#endif
413483
};
414484
// First N entries are common to both drive base classes.
415485
static MP_DEFINE_CONST_DICT(pb_type_DriveBase_locals_dict, pb_type_DriveBase_locals_dict_table);

0 commit comments

Comments
 (0)