Skip to content

Commit 123fb59

Browse files
AP_Periph: add backwards compatibility to GPS_TYPE parameter for auto config
1 parent 8b562d6 commit 123fb59

File tree

4 files changed

+19
-2
lines changed

4 files changed

+19
-2
lines changed

AP_Periph/AP_Periph.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -208,6 +208,10 @@ void AP_Periph_FW::init()
208208
}
209209
}
210210

211+
float value;
212+
AP_Param::get("GPS1_TYPE", value);
213+
AP_Param::set_and_save_by_name("GPS_TYPE", value);
214+
211215
#if AP_SCRIPTING_ENABLED
212216
scripting.init();
213217
#endif

AP_Periph/Parameters.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ extern const AP_HAL::HAL &hal;
3333
#define MAV_SYSTEM_ID HAL_DEFAULT_MAV_SYSTEM_ID
3434
#endif
3535

36+
#define GSCALAR_HIDDEN(v, name, def) { name, &AP_PARAM_VEHICLE_NAME.g.v, {def_value : def}, AP_PARAM_FLAG_HIDDEN, Parameters::k_param_ ## v, AP_PARAM_VEHICLE_NAME.g.v.vtype }
3637
/*
3738
* AP_Periph parameter definitions
3839
*
@@ -100,6 +101,11 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
100101
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
101102
GOBJECT(gps, "GPS", AP_GPS),
102103

104+
// GPS TYPE
105+
// @Param: GPS_TYPE
106+
// @DisplayName: GPS Type
107+
// @Description: GPS Type
108+
GSCALAR_HIDDEN(gps_type, "GPS_TYPE", 0),
103109

104110
#ifdef HAL_PERIPH_ENABLE_MAG
105111
// @Group: COMPASS_

AP_Periph/Parameters.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ class Parameters {
5959
k_param_imu,
6060
k_param_gps_safeboot,
6161
k_param_gps_rover,
62+
k_param_gps_type
6263
};
6364

6465
AP_Int16 format_version;
@@ -105,6 +106,7 @@ class Parameters {
105106
AP_Int8 gps_mb_only_can_port;
106107
AP_Int16 imu_sample_rate;
107108
AP_Int8 gps_safeboot;
109+
AP_Int8 gps_type;
108110
Parameters() {}
109111
};
110112

AP_Periph/can.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -190,8 +190,8 @@ void AP_Periph_DroneCAN::handle_param_getset(const CanardRxTransfer& transfer, c
190190

191191
uavcan_protocol_param_GetSetResponse pkt {};
192192

193-
AP_Param *vp;
194-
enum ap_var_type ptype;
193+
AP_Param *vp, *gps_type_vp;
194+
enum ap_var_type ptype, gps_type_ptype;
195195

196196
if (req.name.len != 0 && req.name.len > AP_MAX_NAME_SIZE) {
197197
vp = nullptr;
@@ -205,6 +205,11 @@ void AP_Periph_DroneCAN::handle_param_getset(const CanardRxTransfer& transfer, c
205205
vp->copy_name_token(token, (char *)pkt.name.data, AP_MAX_NAME_SIZE+1, true);
206206
}
207207
}
208+
if ((req.name.len >= 8) && (strncmp((char* )req.name.data, "GPS_TYPE", 8) == 0) && (req.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE)) {
209+
// set GPS1_TYPE as well
210+
gps_type_vp = AP_Param::find("GPS1_TYPE", &gps_type_ptype);
211+
((AP_Int8*)gps_type_vp)->set_and_save_ifchanged(req.value.integer_value);
212+
}
208213
if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) {
209214
// param set
210215
switch (ptype) {

0 commit comments

Comments
 (0)