Skip to content

Commit 18c0e62

Browse files
Refactoring
1 parent 9801272 commit 18c0e62

File tree

6 files changed

+114
-121
lines changed

6 files changed

+114
-121
lines changed

main.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ void testThreadFunc(void* arg) {
4545

4646

4747
int i = 0;
48-
void gpsUpdated(const xbot::driver::gps::GpsInterface::GpsState &new_state) {
48+
void gpsUpdated(const xbot::driver::gps::GpsDriver::GpsState &new_state) {
4949
(void)new_state;
5050
etl::string<100> lat{};
5151
etl::format_spec format{};
@@ -125,9 +125,9 @@ int main(void) {
125125
mower_service.start();
126126

127127
// chThdCreateStatic(testWa, sizeof(testWa), NORMALPRIO, testThreadFunc, NULL);
128-
gps.set_state_callback(etl::delegate<void(const xbot::driver::gps::GpsInterface::GpsState &new_state)>::create<gpsUpdated>());
129-
gps.set_datum(49.0, 10.0, 150);
130-
gps.start_driver(&UARTD6, 921600);
128+
gps.SetStateCallback(etl::delegate<void(const xbot::driver::gps::GpsDriver::GpsState &new_state)>::create<gpsUpdated>());
129+
gps.SetDatum(49.0, 10.0, 150);
130+
gps.StartDriver(&UARTD6, 921600);
131131

132132
// Subscribe to global events and dispatch to our services
133133
event_listener_t event_listener;

src/drivers/gps/gps_interface.cpp

Lines changed: 32 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -9,53 +9,53 @@
99

1010
#include <cmath>
1111

12-
namespace xbot {
13-
namespace driver {
14-
namespace gps {
1512

16-
GpsInterface::GpsInterface() {
13+
14+
namespace xbot::driver::gps {
15+
16+
GpsDriver::GpsDriver() {
1717
datum_lat_ = datum_long_ = NAN;
1818
}
19-
bool GpsInterface::start_driver(UARTDriver *uart, uint32_t baudrate) {
19+
bool GpsDriver::StartDriver(UARTDriver *uart, uint32_t baudrate) {
2020
chDbgAssert(stopped_, "don't start the driver twice");
2121
chDbgAssert(uart != nullptr, "need to provide a driver");
2222
if(!stopped_) {
2323
return false;
2424
}
25-
this->uart = uart;
26-
uart_config.speed = baudrate;
27-
uart_config.context = this;
28-
bool uartStarted = uartStart(uart, &uart_config) == MSG_OK;
25+
this->uart_ = uart;
26+
uart_config_.speed = baudrate;
27+
uart_config_.context = this;
28+
bool uartStarted = uartStart(uart, &uart_config_) == MSG_OK;
2929
if(!uartStarted) {
3030
return false;
3131
}
3232

3333

34-
uart_config.rxchar_cb = [](UARTDriver* uartp, uint16_t c) {
34+
uart_config_.rxchar_cb = [](UARTDriver* uartp, uint16_t c) {
3535
(void)uartp;
3636
(void)c;
3737
static int missing_bytes=0;
3838
missing_bytes++;
3939
};
4040

41-
uart_config.rxend_cb = [](UARTDriver* uartp) {
41+
uart_config_.rxend_cb = [](UARTDriver* uartp) {
4242
(void)uartp;
4343
static int i = 0;
4444
i++;
45-
GpsInterface* instance = reinterpret_cast<const UARTConfigEx*>(uartp->config)->context;
46-
if(!instance->processing_done) {
45+
GpsDriver* instance = reinterpret_cast<const UARTConfigEx*>(uartp->config)->context;
46+
if(!instance->processing_done_) {
4747
// This is bad, processing is too slow to keep up with updates!
4848
// We just read into the same buffer again
49-
uint8_t* next_recv_buffer = (instance->processing_buffer == instance->recv_buffer1) ? instance->recv_buffer2 : instance->recv_buffer1;
49+
uint8_t* next_recv_buffer = (instance->processing_buffer_ == instance->recv_buffer1_) ? instance->recv_buffer2_ : instance->recv_buffer1_;
5050
uartStartReceiveI(uartp, RECV_BUFFER_SIZE, next_recv_buffer);
5151
} else {
5252
// Swap buffers and read into the next one
5353
// Get the pointer to the receiving buffer (it's not the processing buffer)
54-
uint8_t* next_recv_buffer = instance->processing_buffer;
54+
uint8_t* next_recv_buffer = instance->processing_buffer_;
5555
uartStartReceiveI(uartp, RECV_BUFFER_SIZE, next_recv_buffer);
56-
instance->processing_buffer = (instance->processing_buffer == instance->recv_buffer1) ? instance->recv_buffer2 : instance->recv_buffer1;
57-
instance->processing_buffer_len = RECV_BUFFER_SIZE;
58-
instance->processing_done = false;
56+
instance->processing_buffer_ = (instance->processing_buffer_ == instance->recv_buffer1_) ? instance->recv_buffer2_ : instance->recv_buffer1_;
57+
instance->processing_buffer_len_ = RECV_BUFFER_SIZE;
58+
instance->processing_done_ = false;
5959
// Signal the processing thread
6060
if(instance->processing_thread_) {
6161
chEvtSignalI(instance->processing_thread_, 1);
@@ -66,45 +66,43 @@ bool GpsInterface::start_driver(UARTDriver *uart, uint32_t baudrate) {
6666

6767

6868
stopped_ = false;
69-
processing_thread_ = chThdCreateStatic(&wa, sizeof(wa), NORMALPRIO, threadHelper, this);
69+
processing_thread_ = chThdCreateStatic(&thd_wa_, sizeof(thd_wa_), NORMALPRIO, threadHelper, this);
7070

71-
uartStartReceive(uart, RECV_BUFFER_SIZE, recv_buffer1);
71+
uartStartReceive(uart, RECV_BUFFER_SIZE, recv_buffer1_);
7272
return true;
7373
}
7474

75-
void GpsInterface::set_state_callback(const GpsInterface::StateCallback &function) {
76-
state_callback = function;
75+
void GpsDriver::SetStateCallback(const GpsDriver::StateCallback &function) {
76+
state_callback_ = function;
7777
}
78-
void GpsInterface::set_datum(double datum_lat, double datum_long,
78+
void GpsDriver::SetDatum(double datum_lat, double datum_long,
7979
double datum_height) {
8080
datum_lat_ = datum_lat;
8181
datum_long_ = datum_long;
8282
datum_u_ = datum_height;
8383
}
8484

85-
bool GpsInterface::send_raw(const void *data, size_t size) {
85+
bool GpsDriver::send_raw(const void *data, size_t size) {
8686
// sdWrite(uart, static_cast<const uint8_t*>(data), size);
87-
uartSendFullTimeout(uart, &size, data, TIME_INFINITE);
87+
uartSendFullTimeout(uart_, &size, data, TIME_INFINITE);
8888
return true;
8989
}
9090

91-
void GpsInterface::threadFunc() {
91+
void GpsDriver::threadFunc() {
9292
while(!stopped_) {
9393
// Wait for data to arrive, process and mark as done
9494
chEvtWaitAny(ALL_EVENTS);
95-
process_bytes(processing_buffer, processing_buffer_len);
96-
processing_done = true;
95+
ProcessBytes(processing_buffer_, processing_buffer_len_);
96+
processing_done_ = true;
9797
}
9898
}
9999

100-
void GpsInterface::threadHelper(void *instance) {
101-
auto *gps_interface = static_cast<GpsInterface *>(instance);
100+
void GpsDriver::threadHelper(void *instance) {
101+
auto *gps_interface = static_cast<GpsDriver *>(instance);
102102
gps_interface->threadFunc();
103103
}
104104

105-
void GpsInterface::send_rtcm(const uint8_t *data, size_t size) {
105+
void GpsDriver::SendRTCM(const uint8_t *data, size_t size) {
106106
send_raw(data, size);
107107
}
108-
} // namespace gps
109-
} // namespace driver
110-
} // namespace xbot
108+
} // namespace xbot::driver::gps

src/drivers/gps/gps_interface.h

Lines changed: 27 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -2,22 +2,20 @@
22
// Created by clemens on 10.01.23.
33
//
44

5-
#ifndef OPEN_MOWER_ROS_GPS_INTERFACE_H
6-
#define OPEN_MOWER_ROS_GPS_INTERFACE_H
5+
#ifndef XBOT_DRIVER_GPS_GPS_INTERFACE_H
6+
#define XBOT_DRIVER_GPS_GPS_INTERFACE_H
77

88
#include <etl/delegate.h>
99

1010
#include "ch.h"
1111
#include "hal.h"
1212

13-
namespace xbot {
14-
namespace driver {
15-
namespace gps {
16-
class GpsInterface {
13+
namespace xbot::driver::gps {
14+
class GpsDriver {
1715
public:
18-
explicit GpsInterface();
16+
explicit GpsDriver();
1917

20-
virtual ~GpsInterface() = default;
18+
virtual ~GpsDriver() = default;
2119

2220
/*
2321
* The final GPS state we're interested in.
@@ -60,17 +58,15 @@ class GpsInterface {
6058
typedef etl::delegate<void(const GpsState &new_state)> StateCallback;
6159

6260
public:
63-
bool start_driver(UARTDriver *uart, uint32_t baudrate);
64-
void set_state_callback(const GpsInterface::StateCallback &function);
61+
bool StartDriver(UARTDriver *uart, uint32_t baudrate);
62+
void SetStateCallback(const GpsDriver::StateCallback &function);
6563

66-
void set_datum(double datum_lat, double datum_long, double datum_height);
64+
void SetDatum(double datum_lat, double datum_long, double datum_height);
6765

68-
void send_rtcm(const uint8_t *data, size_t size);
69-
70-
void read_uart(uint32_t timeout);
66+
void SendRTCM(const uint8_t *data, size_t size);
7167

7268
protected:
73-
StateCallback state_callback{};
69+
StateCallback state_callback_{};
7470

7571
double datum_lat_ = 0, datum_long_ = 0, datum_u_ = 0;
7672

@@ -84,38 +80,38 @@ class GpsInterface {
8480
bool send_raw(const void *data, size_t size);
8581

8682
// Called on serial reconnect
87-
virtual void reset_parser_state() = 0;
83+
virtual void ResetParserState() = 0;
8884

89-
virtual size_t process_bytes(const uint8_t *buffer, size_t len) = 0;
85+
virtual size_t ProcessBytes(const uint8_t *buffer, size_t len) = 0;
9086

9187
private:
9288
// Extend the config struct by a pointer to this instance, so that we can access it in callbacks.
93-
struct UARTConfigEx : public UARTConfig {
94-
GpsInterface *context;
89+
struct UARTConfigEx : UARTConfig {
90+
GpsDriver *context;
9591
};
9692

9793
static constexpr size_t RECV_BUFFER_SIZE = 100;
9894
// Keep two buffers for streaming data while doing processing
99-
uint8_t recv_buffer1[RECV_BUFFER_SIZE]{};
100-
uint8_t recv_buffer2[RECV_BUFFER_SIZE]{};
95+
uint8_t recv_buffer1_[RECV_BUFFER_SIZE]{};
96+
uint8_t recv_buffer2_[RECV_BUFFER_SIZE]{};
10197
// We start by receiving into recv_buffer1, so processing_buffer is the 2 (but empty)
102-
uint8_t *volatile processing_buffer = recv_buffer2;
103-
volatile size_t processing_buffer_len = 0;
98+
uint8_t *volatile processing_buffer_ = recv_buffer2_;
99+
volatile size_t processing_buffer_len_ = 0;
104100

105-
UARTDriver *uart{};
106-
UARTConfigEx uart_config{};
101+
UARTDriver *uart_{};
102+
UARTConfigEx uart_config_{};
107103

108-
THD_WORKING_AREA(wa, 512){};
104+
THD_WORKING_AREA(thd_wa_, 512){};
109105
thread_t *processing_thread_ = nullptr;
110106
// This is reset by the receiving ISR and set by the thread to signal if it's safe to process more data.
111-
volatile bool processing_done = true;
107+
volatile bool processing_done_ = true;
112108
bool stopped_ = true;
113109

114110
void threadFunc();
115111

116112
static void threadHelper(void *instance);
117113
};
118-
} // namespace gps
119-
} // namespace driver
120-
} // namespace xbot
121-
#endif // OPEN_MOWER_ROS_GPS_INTERFACE_H
114+
} // namespace xbot::driver::gps
115+
116+
117+
#endif // XBOT_DRIVER_GPS_GPS_INTERFACE_H

0 commit comments

Comments
 (0)