septentrio: add single wire uart option

This commit is contained in:
Alexander Lerach 2025-06-03 16:02:26 +02:00
parent 0e32b155f3
commit 31041d7410
No known key found for this signature in database
GPG Key ID: E519F0596277508F
3 changed files with 57 additions and 9 deletions

View File

@ -1,12 +1,22 @@
module_name: Septentrio
serial_config:
- command: set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM}"
- command: |
if param compare SEP_PORT2_S_WIRE 1
then
set DUAL_SEP_ARGS "${DUAL_SEP_ARGS} -t"
fi
set DUAL_GPS_ARGS "-e ${SERIAL_DEV} -g p:${BAUD_PARAM} ${DUAL_SEP_ARGS}"
port_config_param:
name: SEP_PORT2_CFG
group: Septentrio
label: Secondary GPS port
- command: septentrio start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${DUAL_GPS_ARGS}
- command: |
if param compare SEP_PORT1_S_WIRE 1
then
set SEP_ARGS "${SEP_ARGS} -s"
fi
septentrio start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} ${SEP_ARGS} ${DUAL_GPS_ARGS}
port_config_param:
name: SEP_PORT1_CFG
group: Septentrio
@ -15,6 +25,22 @@ serial_config:
parameters:
- group: Septentrio
definitions:
SEP_PORT1_S_WIRE:
description:
short: Use single wire UART on SEP_PORT1
long: |
Sets whether single wire UART should be used on SEP_PORT1.
type: boolean
default: 0
reboot_required: true
SEP_PORT2_S_WIRE:
description:
short: Use single wire UART on SEP_PORT2
long: |
Sets whether single wire UART should be used on SEP_PORT2.
type: boolean
default: 0
reboot_required: true
SEP_STREAM_MAIN:
description:
short: Main stream used during automatic configuration

View File

@ -144,10 +144,12 @@ uint32_t SeptentrioDriver::k_supported_baud_rates[] {0, 38400, 57600, 115200, 23
uint32_t SeptentrioDriver::k_default_baud_rate {230400};
orb_advert_t SeptentrioDriver::k_mavlink_log_pub {nullptr};
SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate) :
SeptentrioDriver::SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate,
bool single_wire_uart) :
Device(MODULE_NAME),
_instance(instance),
_chosen_baud_rate(baud_rate)
_chosen_baud_rate(baud_rate),
_single_wire_uart(single_wire_uart)
{
strncpy(_port, device_path, sizeof(_port) - 1);
// Enforce null termination.
@ -253,7 +255,8 @@ int SeptentrioDriver::print_status()
break;
}
PX4_INFO("health: %s, port: %s, baud rate: %lu", is_healthy() ? "OK" : "NOT OK", _port, _uart.getBaudrate());
PX4_INFO("health: %s, port: %s, baud rate: %lu, single wire UART: %u", is_healthy() ? "OK" : "NOT OK", _port,
_uart.getBaudrate(), _single_wire_uart);
PX4_INFO("controller -> receiver data rate: %lu B/s", output_data_rate());
PX4_INFO("receiver -> controller data rate: %lu B/s", input_data_rate());
PX4_INFO("sat info: %s", (_message_satellite_info != nullptr) ? "enabled" : "disabled");
@ -278,6 +281,10 @@ void SeptentrioDriver::run()
_uart.setPort(_port);
if (_uart.open()) {
if (_single_wire_uart) {
_uart.setSingleWireMode();
}
_state = State::DetectingBaudRate;
} else {
@ -465,7 +472,8 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance
if (instance == Instance::Main) {
if (Serial::validatePort(arguments.device_path_main)) {
gps = new SeptentrioDriver(arguments.device_path_main, instance,
valid_chosen_baud_rate ? arguments.baud_rate_main : k_default_baud_rate);
valid_chosen_baud_rate ? arguments.baud_rate_main : k_default_baud_rate,
arguments.single_wire_uart_main);
} else {
PX4_ERR("Invalid device (-d) %s", arguments.device_path_main ? arguments.device_path_main : "");
@ -482,7 +490,8 @@ SeptentrioDriver *SeptentrioDriver::instantiate(int argc, char *argv[], Instance
} else {
if (Serial::validatePort(arguments.device_path_secondary)) {
gps = new SeptentrioDriver(arguments.device_path_secondary, instance,
valid_chosen_baud_rate ? arguments.baud_rate_secondary : k_default_baud_rate);
valid_chosen_baud_rate ? arguments.baud_rate_secondary : k_default_baud_rate,
arguments.single_wire_uart_secondary);
} else {
PX4_ERR("Invalid secondary device (-e) %s", arguments.device_path_secondary ? arguments.device_path_secondary : "");
@ -570,6 +579,8 @@ $ gps reset warm
PRINT_MODULE_USAGE_PARAM_INT('b', 0, 57600, 1500000, "Primary receiver baud rate", true);
PRINT_MODULE_USAGE_PARAM_STRING('e', nullptr, "<file:dev>", "Secondary receiver port", true);
PRINT_MODULE_USAGE_PARAM_INT('g', 0, 57600, 1500000, "Secondary receiver baud rate", true);
PRINT_MODULE_USAGE_PARAM_FLAG('s', "Primary receiver, use single wire UART", true);
PRINT_MODULE_USAGE_PARAM_FLAG('t', "Secondary receiver, use single wire UART", true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reset connected receiver");
@ -627,7 +638,7 @@ int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArgument
int myoptind{1};
const char *myoptarg{nullptr};
while ((ch = px4_getopt(argc, argv, "d:e:b:g:", &myoptind, &myoptarg)) != EOF) {
while ((ch = px4_getopt(argc, argv, "d:e:b:g:st", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'b':
if (px4_get_parameter_value(myoptarg, arguments.baud_rate_main) != 0) {
@ -649,6 +660,14 @@ int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArgument
arguments.device_path_secondary = myoptarg;
break;
case 's':
arguments.single_wire_uart_main = true;
break;
case 't':
arguments.single_wire_uart_secondary = true;
break;
case '?':
return PX4_ERROR;

View File

@ -76,6 +76,8 @@ struct ModuleArguments {
int baud_rate_secondary {0};
const char *device_path_main {nullptr};
const char *device_path_secondary {nullptr};
bool single_wire_uart_main {false};
bool single_wire_uart_secondary {false};
};
/**
@ -229,7 +231,7 @@ enum class ReceiverOutputTracker {
class SeptentrioDriver : public ModuleBase<SeptentrioDriver>, public device::Device
{
public:
SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate);
SeptentrioDriver(const char *device_path, Instance instance, uint32_t baud_rate, bool single_wire_uart);
~SeptentrioDriver() override;
/** @see ModuleBase */
@ -715,6 +717,7 @@ private:
bool _time_synced {false}; ///< Receiver time in sync with GPS time
const Instance _instance {Instance::Main}; ///< The receiver that this instance of the driver controls
uint32_t _chosen_baud_rate {0}; ///< The baud rate requested by the user
bool _single_wire_uart {false}; ///< Whether single wire UART should be used
static px4::atomic<SeptentrioDriver *> _secondary_instance;
hrt_abstime _sleep_end {0}; ///< End time for sleeping
State _resume_state {State::OpeningSerialPort}; ///< Resume state after sleep