mirror of https://github.com/ArduPilot/ardupilot
Tools: allow forwards/backwards for DroneCAN type autoconfig
ArduPilot configures a connected DroneCAN GPS based on its GPS Type. Given parameter name changes, ArduPilot must be able to configure both new and old AP_Periphs, and new AP_Periphs have to cope with being configured by old ArduPilots.
This commit is contained in:
parent
2a010623b2
commit
7e1a3ae4dc
|
@ -142,6 +142,7 @@ void AP_Periph_FW::init()
|
|||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||
gps.set_default_type_for_gps1(HAL_GPS1_TYPE_DEFAULT);
|
||||
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
|
||||
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
|
|
@ -223,6 +223,11 @@ void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,
|
|||
total_size);
|
||||
}
|
||||
|
||||
// compatability code added Mar 2024 for 4.6:
|
||||
#ifndef AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
|
||||
#define AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED 1
|
||||
#endif
|
||||
|
||||
/*
|
||||
handle parameter GetSet request
|
||||
*/
|
||||
|
@ -245,7 +250,18 @@ void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRx
|
|||
vp = nullptr;
|
||||
} else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) {
|
||||
memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);
|
||||
#if AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
|
||||
// cope with older versions of ArduPilot attempting to
|
||||
// auto-configure AP_Periph using "GPS_TYPE" by
|
||||
// auto-converting to "GPS1_TYPE":
|
||||
if (strncmp((char*)req.name.data, "GPS_TYPE", req.name.len) == 0) {
|
||||
vp = AP_Param::find("GPS1_TYPE", &ptype);
|
||||
} else {
|
||||
vp = AP_Param::find((char *)pkt.name.data, &ptype);
|
||||
}
|
||||
#else
|
||||
vp = AP_Param::find((char *)pkt.name.data, &ptype);
|
||||
#endif
|
||||
} else {
|
||||
AP_Param::ParamToken token {};
|
||||
vp = AP_Param::find_by_index(req.index, &ptype, &token);
|
||||
|
|
Loading…
Reference in New Issue