Skip to content

Commit f1e563d

Browse files
committed
Run clang-tidy
1 parent ccc7bab commit f1e563d

5 files changed

Lines changed: 73 additions & 63 deletions

File tree

src/Primitives/Mindstorms/Motor.cpp

Lines changed: 17 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,9 @@
11
#include "Motor.h"
2+
23
#include "../../Utils/macros.h"
34

4-
MotorEncoder::MotorEncoder(gpio_dt_spec pin5_encoder_spec, gpio_dt_spec pin6_encoder_spec, const char *name)
5+
MotorEncoder::MotorEncoder(gpio_dt_spec pin5_encoder_spec,
6+
gpio_dt_spec pin6_encoder_spec, const char *name)
57
: pin5_encoder_spec(pin5_encoder_spec),
68
pin6_encoder_spec(pin6_encoder_spec),
79
angle(0),
@@ -14,10 +16,11 @@ MotorEncoder::MotorEncoder(gpio_dt_spec pin5_encoder_spec, gpio_dt_spec pin6_enc
1416
FATAL("Failed to configure GPIO encoder pin6\n");
1517
}
1618

17-
int result = gpio_pin_interrupt_configure_dt(&pin6_encoder_spec,
18-
GPIO_INT_EDGE_RISING | GPIO_INT_EDGE_FALLING);
19+
int result = gpio_pin_interrupt_configure_dt(
20+
&pin6_encoder_spec, GPIO_INT_EDGE_RISING | GPIO_INT_EDGE_FALLING);
1921
if (result != 0) {
20-
printf("Failed to configure interrupt on pin6 for %s, error code %d\n", name, result);
22+
printf("Failed to configure interrupt on pin6 for %s, error code %d\n",
23+
name, result);
2124
}
2225
gpio_init_callback(&pin6_encoder_cb_data,
2326
MotorEncoder::encoder_pin6_edge_rising,
@@ -55,9 +58,7 @@ Motor::Motor(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec,
5558
MotorEncoder *encoder)
5659
: pwm1_spec(pwm1_spec), pwm2_spec(pwm2_spec), encoder(encoder) {}
5760

58-
void Motor::halt() {
59-
drive_pwm(pwm1_spec, pwm2_spec, 1.0f, 1.0f);
60-
}
61+
void Motor::halt() { drive_pwm(pwm1_spec, pwm2_spec, 1.0f, 1.0f); }
6162

6263
bool Motor::set_speed(float speed) {
6364
float pwm1 = 0;
@@ -72,29 +73,31 @@ bool Motor::set_speed(float speed) {
7273
}
7374

7475
void Motor::drive_to_target(int32_t speed) {
75-
printf("drift = %d\n",
76-
abs(get_drift()));
76+
printf("drift = %d\n", abs(get_drift()));
7777

7878
int drift = get_drift();
7979
// Reset stall timer, otherwise it will instantly think it's not moving.
8080
encoder->last_update = k_uptime_get();
8181
while (abs(drift) > 0) {
8282
int speed_sign = std::signbit(drift) ? -1 : 1;
8383
set_speed(speed_sign * speed / 10000.0f);
84-
while (speed_sign *
85-
(get_drift()) >
86-
0 &&
84+
while (speed_sign * (get_drift()) > 0 &&
8785
k_uptime_get() - encoder->get_last_update() < 150) {
8886
}
8987
bool not_moving = k_uptime_get() - encoder->get_last_update() >= 150;
9088
if (not_moving) {
9189
speed += 100;
92-
printf("Not moving, increasing speed to %d, %llims since last movement\n", speed, k_uptime_get() - encoder->get_last_update());
90+
printf(
91+
"Not moving, increasing speed to %d, %llims since last "
92+
"movement\n",
93+
speed, k_uptime_get() - encoder->get_last_update());
9394
set_speed(speed_sign * speed / 10000.0f);
9495

9596
// Wait for 10ms or movement.
9697
uint64_t start_time = k_uptime_get();
97-
while (k_uptime_get() - start_time < 10 && k_uptime_get() - encoder->get_last_update() >= 150) {}
98+
while (k_uptime_get() - start_time < 10 &&
99+
k_uptime_get() - encoder->get_last_update() >= 150) {
100+
}
98101
continue;
99102
}
100103
encoder->last_update = k_uptime_get();

src/Primitives/Mindstorms/Motor.h

Lines changed: 13 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,19 @@
11
#ifndef WARDUINO_MOTOR_H
22
#define WARDUINO_MOTOR_H
33

4-
#include <cstdint>
5-
#include <cmath>
6-
74
#include <zephyr/drivers/gpio.h>
85
#include <zephyr/drivers/pwm.h>
96
#include <zephyr/kernel.h>
107

8+
#include <cmath>
9+
#include <cstdint>
10+
1111
class MotorEncoder {
1212
static void encoder_pin6_edge_rising(const struct device *dev,
1313
struct gpio_callback *cb,
1414
uint32_t pins) {
15-
MotorEncoder *encoder = CONTAINER_OF(cb, MotorEncoder, pin6_encoder_cb_data);
15+
MotorEncoder *encoder =
16+
CONTAINER_OF(cb, MotorEncoder, pin6_encoder_cb_data);
1617

1718
int rising = gpio_pin_get_raw(encoder->pin6_encoder_spec.port,
1819
encoder->pin6_encoder_spec.pin);
@@ -35,8 +36,9 @@ class MotorEncoder {
3536
encoder->last_update = k_uptime_get();
3637
}
3738

38-
public:
39-
MotorEncoder(gpio_dt_spec pin5_encoder_spec, gpio_dt_spec pin6_encoder_spec, const char *name);
39+
public:
40+
MotorEncoder(gpio_dt_spec pin5_encoder_spec, gpio_dt_spec pin6_encoder_spec,
41+
const char *name);
4042

4143
~MotorEncoder();
4244

@@ -52,20 +54,20 @@ class MotorEncoder {
5254

5355
[[nodiscard]] inline int64_t get_last_update() const { return last_update; }
5456

55-
private:
57+
private:
5658
gpio_dt_spec pin5_encoder_spec;
5759
gpio_dt_spec pin6_encoder_spec;
5860
struct gpio_callback pin5_encoder_cb_data;
5961
struct gpio_callback pin6_encoder_cb_data;
6062
volatile int angle;
6163
int target_angle;
6264

63-
public:
65+
public:
6466
volatile int64_t last_update;
6567
};
6668

6769
class Motor {
68-
public:
70+
public:
6971
Motor(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec, MotorEncoder *encoder);
7072

7173
pwm_dt_spec pwm1_spec;
@@ -87,6 +89,7 @@ bool drive_pwm(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec, float pwm1,
8789

8890
bool drive_motor(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec, float speed);
8991

90-
void drive_motor_to_target(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec, MotorEncoder *encoder, int32_t speed);
92+
void drive_motor_to_target(pwm_dt_spec pwm1_spec, pwm_dt_spec pwm2_spec,
93+
MotorEncoder *encoder, int32_t speed);
9194

9295
#endif // WARDUINO_MOTOR_H

src/Primitives/Mindstorms/uart_sensor.cpp

Lines changed: 20 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,11 @@
11
#include "uart_sensor.h"
22

3-
#include <cstdio>
43
#include <zephyr/drivers/uart.h>
54

5+
#include <cstdio>
6+
67
void serial_cb(const struct device *dev, void *user_data) {
7-
auto *sensor = static_cast<UartSensor*>(user_data);
8+
auto *sensor = static_cast<UartSensor *>(user_data);
89
uint8_t data;
910

1011
if (!uart_irq_update(dev)) {
@@ -16,6 +17,8 @@ void serial_cb(const struct device *dev, void *user_data) {
1617
}
1718

1819
while (uart_fifo_read(dev, &data, 1) == 1) {
20+
// printf("data: 0x%02x %c\n", data, data);
21+
1922
if (sensor->receive_state == ReceiveState::data) {
2023
if (sensor->data_byte) {
2124
sensor->sensor_value = data;
@@ -34,20 +37,22 @@ void serial_cb(const struct device *dev, void *user_data) {
3437
sensor->payload_bytes--;
3538

3639
if (sensor->payload_bytes > 1) {
37-
if (sensor->receive_state == ReceiveState::final_mode_format && sensor->payload_bytes == 5 && data != 0x80) {
40+
if (sensor->receive_state == ReceiveState::final_mode_format &&
41+
sensor->payload_bytes == 5 && data != 0x80) {
3842
sensor->receive_state = ReceiveState::advertise;
3943
sensor->payload_bytes = 0;
4044
}
4145
sensor->checksum ^= data;
42-
sensor->current_payload = sensor->current_payload |
43-
(((unsigned long)data) << sensor->payload_index * 8);
46+
sensor->current_payload =
47+
sensor->current_payload |
48+
(((unsigned long)data) << sensor->payload_index * 8);
4449
sensor->payload_index++;
4550
} else if (sensor->checksum == data) {
4651
if (sensor->receive_state == ReceiveState::advertise) {
4752
printf("Baudrate = %d\n", sensor->current_payload);
48-
sensor->baudrate = (int) sensor->current_payload;
49-
}
50-
else if (sensor->receive_state == ReceiveState::final_mode_format){
53+
sensor->baudrate = (int)sensor->current_payload;
54+
} else if (sensor->receive_state ==
55+
ReceiveState::final_mode_format) {
5156
sensor->receive_state = ReceiveState::modes_complete;
5257
}
5358
}
@@ -58,7 +63,8 @@ void serial_cb(const struct device *dev, void *user_data) {
5863
// If we receive an ACK after the final format message and we
5964
// know which speed to communicate at then we should send an ACK to
6065
// switch to data mode.
61-
if (sensor->receive_state == ReceiveState::modes_complete && sensor->baudrate > 0) {
66+
if (sensor->receive_state == ReceiveState::modes_complete &&
67+
sensor->baudrate > 0) {
6268
printf("Completing pairing sequence\n");
6369
uart_poll_out(dev, 0b00000100); // Send ACK back
6470
sensor->receive_state = ReceiveState::data;
@@ -93,8 +99,8 @@ void set_sensor_mode(UartSensor *sensor, uint8_t new_mode) {
9399
uart_poll_out(sensor->dev, new_mode);
94100
uart_poll_out(sensor->dev, 0xff ^ 0x43 ^ new_mode);
95101

96-
// Invalidate current sensor values. This prevents the program reading values that it normally cannot read in a
97-
// particular mode.
102+
// Invalidate current sensor values. This prevents the program reading
103+
// values that it normally cannot read in a particular mode.
98104
sensor->sensor_value = -1;
99105
}
100106

@@ -117,7 +123,8 @@ bool configure_uart_sensor(UartSensor *sensor, uint8_t new_mode) {
117123
return false;
118124
}
119125
uart_irq_rx_enable(sensor->dev);
120-
if (sensor->receive_state == ReceiveState::data && sensor->mode != new_mode) {
126+
if (sensor->receive_state == ReceiveState::data &&
127+
sensor->mode != new_mode) {
121128
set_sensor_mode(sensor, new_mode);
122129
}
123130
sensor->mode = new_mode;
@@ -153,9 +160,7 @@ void uartHeartbeat(UartSensor *sensor) {
153160
uart_poll_out(sensor->dev, 0b00000010);
154161
}
155162

156-
bool sensor_ready(UartSensor *sensor) {
157-
return device_is_ready(sensor->dev);
158-
}
163+
bool sensor_ready(UartSensor *sensor) { return device_is_ready(sensor->dev); }
159164

160165
int get_sensor_value(UartSensor *sensor) {
161166
if (!sensor->baudrate_configured || sensor->sensor_value < 0) {

src/Primitives/Mindstorms/uart_sensor.h

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,9 @@
11
#pragma once
2-
#include <cstdint>
32
#include <zephyr/device.h>
43

5-
enum ReceiveState {
6-
advertise,
7-
final_mode_format,
8-
modes_complete,
9-
data
10-
};
4+
#include <cstdint>
5+
6+
enum ReceiveState { advertise, final_mode_format, modes_complete, data };
117

128
struct UartSensor {
139
// Variables used for setting up the sensor.

src/Primitives/zephyr.cpp

Lines changed: 20 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,13 @@
2727
#include "../Memory/mem.h"
2828
#include "../Utils/macros.h"
2929
#include "../Utils/util.h"
30-
#include "primitives.h"
3130
#include "Mindstorms/Motor.h"
3231
#include "Mindstorms/uart_sensor.h"
32+
#include "primitives.h"
3333

3434
#define OBB_PRIMITIVES 0
3535
#ifdef CONFIG_BOARD_STM32L496G_DISCO
36-
#define OBB_PRIMITIVES 6
36+
#define OBB_PRIMITIVES 6
3737
#endif
3838
#define ALL_PRIMITIVES OBB_PRIMITIVES + 6
3939

@@ -304,18 +304,19 @@ MotorEncoder *encoders[] = {new MotorEncoder(specs[51], specs[50], "Port A"),
304304
new MotorEncoder(specs[17], specs[13], "Port C"),
305305
new MotorEncoder(specs[27], specs[26], "Port D")};
306306

307-
#define PWM_SPEC_GETTER(node_id, prop, idx) PWM_DT_SPEC_GET_BY_IDX(DT_PATH(zephyr_user), idx)
308-
struct pwm_dt_spec pwm_specs[] = {
309-
DT_FOREACH_PROP_ELEM_SEP(DT_PATH(zephyr_user), pwms,
310-
PWM_SPEC_GETTER, (,))
311-
};
307+
#define PWM_SPEC_GETTER(node_id, prop, idx) \
308+
PWM_DT_SPEC_GET_BY_IDX(DT_PATH(zephyr_user), idx)
309+
struct pwm_dt_spec pwm_specs[] = {DT_FOREACH_PROP_ELEM_SEP(
310+
DT_PATH(zephyr_user), pwms, PWM_SPEC_GETTER, (, ))};
312311

313312
std::optional<Motor> get_motor(uint32_t motor_index) {
314-
if (motor_index > sizeof(encoders)/sizeof(*encoders)) {
313+
if (motor_index > sizeof(encoders) / sizeof(*encoders)) {
315314
return {};
316315
}
317316

318-
return std::make_optional<Motor>(pwm_specs[motor_index * 2 + 1], pwm_specs[motor_index * 2], encoders[motor_index]);
317+
return std::make_optional<Motor>(pwm_specs[motor_index * 2 + 1],
318+
pwm_specs[motor_index * 2],
319+
encoders[motor_index]);
319320
}
320321

321322
def_prim(drive_motor, twoToNoneU32) {
@@ -364,17 +365,20 @@ def_prim(drive_motor_ms, threeToNoneU32) {
364365
return false;
365366
}
366367

367-
bool drive_motor_degrees_absolute(uint32_t motor_index, int32_t degrees, int32_t speed) {
368+
bool drive_motor_degrees_absolute(uint32_t motor_index, int32_t degrees,
369+
int32_t speed) {
368370
if (auto motor = get_motor(motor_index)) {
369371
motor->drive_to_angle(speed, degrees);
370372
return true;
371373
}
372374
return false;
373375
}
374376

375-
bool drive_motor_degrees_relative(uint32_t motor_index, int32_t degrees, int32_t speed) {
377+
bool drive_motor_degrees_relative(uint32_t motor_index, int32_t degrees,
378+
int32_t speed) {
376379
MotorEncoder *encoder = encoders[motor_index];
377-
return drive_motor_degrees_absolute(motor_index, encoder->get_target_angle() + degrees, speed);
380+
return drive_motor_degrees_absolute(
381+
motor_index, encoder->get_target_angle() + degrees, speed);
378382
}
379383

380384
def_prim(drive_motor_degrees, threeToNoneU32) {
@@ -398,7 +402,8 @@ def_prim_reverse(drive_motor_degrees) {
398402
// primitives instead of after and just not restore io when
399403
// restoring the last snapshot and transfer overrides from a future
400404
// snapshot when doing forward execution.
401-
drive_motor_degrees_absolute(motor_index, (int32_t) state.value, motor_index == 0 ? 10000 : 2000);
405+
drive_motor_degrees_absolute(motor_index, (int32_t)state.value,
406+
motor_index == 0 ? 10000 : 2000);
402407
}
403408
}
404409
}
@@ -414,7 +419,7 @@ def_prim_serialize(drive_motor_degrees) {
414419
}
415420

416421
static const struct device *const uart_dev =
417-
DEVICE_DT_GET(DT_PROP(DT_PATH(zephyr_user), warduino_uarts));
422+
DEVICE_DT_GET(DT_PROP(DT_PATH(zephyr_user), warduino_uarts));
418423

419424
UartSensor sensor(uart_dev);
420425

@@ -439,9 +444,7 @@ def_prim(color_sensor, oneToOneU32) {
439444

440445
extern void read_debug_messages();
441446

442-
void debug_work_handler(struct k_work *work) {
443-
read_debug_messages();
444-
}
447+
void debug_work_handler(struct k_work *work) { read_debug_messages(); }
445448

446449
K_WORK_DEFINE(debug_work, debug_work_handler);
447450

0 commit comments

Comments
 (0)