mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_Linux: UARTDriver, const device_path
Class member set to const and set_device_path accepts a const char* now.
This commit is contained in:
parent
790f4ec56c
commit
309511dc08
@ -45,7 +45,7 @@ LinuxUARTDriver::LinuxUARTDriver(bool default_console) :
|
|||||||
/*
|
/*
|
||||||
set the tty device to use for this UART
|
set the tty device to use for this UART
|
||||||
*/
|
*/
|
||||||
void LinuxUARTDriver::set_device_path(char *path)
|
void LinuxUARTDriver::set_device_path(const char *path)
|
||||||
{
|
{
|
||||||
device_path = path;
|
device_path = path;
|
||||||
}
|
}
|
||||||
|
@ -25,7 +25,7 @@ public:
|
|||||||
size_t write(uint8_t c);
|
size_t write(uint8_t c);
|
||||||
size_t write(const uint8_t *buffer, size_t size);
|
size_t write(const uint8_t *buffer, size_t size);
|
||||||
|
|
||||||
void set_device_path(char *path);
|
void set_device_path(const char *path);
|
||||||
|
|
||||||
virtual void _timer_tick(void);
|
virtual void _timer_tick(void);
|
||||||
|
|
||||||
@ -58,7 +58,7 @@ private:
|
|||||||
uint64_t _last_write_time;
|
uint64_t _last_write_time;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
char *device_path;
|
const char *device_path;
|
||||||
volatile bool _initialised;
|
volatile bool _initialised;
|
||||||
// we use in-task ring buffers to reduce the system call cost
|
// we use in-task ring buffers to reduce the system call cost
|
||||||
// of ::read() and ::write() in the main loop
|
// of ::read() and ::write() in the main loop
|
||||||
|
Loading…
Reference in New Issue
Block a user