Skip to content

Commit b97a9f0

Browse files
committed
x
1 parent 35f6f16 commit b97a9f0

5 files changed

Lines changed: 48 additions & 9 deletions

File tree

libraries/AP_GPS/AP_GPS.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -297,6 +297,18 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
297297
AP_SUBGROUPINFO(params[5], "6_", 37, AP_GPS, AP_GPS::Params),
298298
#endif
299299

300+
#if GPS_MAX_INSTANCES > 6
301+
// @Group: 7_
302+
// @Path: AP_GPS_Params.cpp
303+
AP_SUBGROUPINFO(params[6], "7_", 38, AP_GPS, AP_GPS::Params),
304+
#endif
305+
306+
#if GPS_MAX_INSTANCES > 7
307+
// @Group: 8_
308+
// @Path: AP_GPS_Params.cpp
309+
AP_SUBGROUPINFO(params[7], "8_", 38, AP_GPS, AP_GPS::Params),
310+
#endif
311+
300312
AP_GROUPEND
301313
};
302314

libraries/AP_GPS/AP_GPS.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,9 @@ class AP_GPS
149149
#if GPS_MOVING_BASELINE
150150
MovingBase mb_params;
151151
#endif // GPS_MOVING_BASELINE
152-
152+
#if AP_GPS_BLENDED_ENABLED
153+
AP_Int8 blend_mask;
154+
#endif
153155
static const struct AP_Param::GroupInfo var_info[];
154156
};
155157

libraries/AP_GPS/AP_GPS_Blended.cpp

Lines changed: 22 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,25 @@
1111

1212
#define BLEND_COUNTER_FAILURE_INCREMENT 10
1313

14+
// returns true if the instance at offset i should be included in this blend
15+
bool AP_GPS_Blended::should_include_instance_in_blend(uint8_t i) const
16+
{
17+
// do not blend blending backends (including this one!) This
18+
// probably wants to be a "gps.provides_real_sensor_data()"
19+
// callback when we add a median-filter backend
20+
if (gps.params[i].type == AP_GPS::GPS_TYPE_BLENDED) {
21+
return false;
22+
}
23+
if (gps.state[i].status <= AP_GPS::GPS_OK_FIX_2D) {
24+
return false;
25+
}
26+
if ((params.mask & (1U<<i)) == 0) {
27+
return false;
28+
}
29+
30+
return true;
31+
}
32+
1433
/*
1534
calculate the weightings used to blend GPSs location and velocity data
1635
*/
@@ -32,10 +51,7 @@ bool AP_GPS_Blended::_calc_weights(void)
3251
// don't blend blended backends (including ourself...). This
3352
// probably wants to be a "gps.provides_real_sensor_data()"
3453
// callback when we add a median-filter backend
35-
if (gps.params[i].type == AP_GPS::GPS_TYPE_BLENDED) {
36-
continue;
37-
}
38-
if (gps.state[i].status <= AP_GPS::NO_FIX) {
54+
if (!should_include_instance_in_blend(i)) {
3955
continue;
4056
}
4157
good_fix_count += 1;
@@ -50,9 +66,7 @@ bool AP_GPS_Blended::_calc_weights(void)
5066
uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message
5167
uint32_t max_rate_ms = 0; // largest update interval of a GPS receiver
5268
for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) {
53-
// don't blend blended backends (including ourself...). This
54-
// probably wants to be a "gps.provides_real_sensor_data()"
55-
// callback when we add a median-filter backend
69+
// don't blend blended backends (including ourself...).
5670
if (gps.params[i].type == AP_GPS::GPS_TYPE_BLENDED) {
5771
continue;
5872
}
@@ -252,7 +266,7 @@ bool AP_GPS_Blended::_calc_weights(void)
252266
// don't blend blended backends (including ourself...). This
253267
// probably wants to be a "gps.provides_real_sensor_data()"
254268
// callback when we add a median-filter backend
255-
if (gps.params[i].type == AP_GPS::GPS_TYPE_BLENDED) {
269+
if (!should_include_instance_in_blend(i)) {
256270
continue;
257271
}
258272
_blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;

libraries/AP_GPS/AP_GPS_Blended.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,9 @@ class AP_GPS_Blended : public AP_GPS_Backend
7676
AP_GPS::GPS_Status _highest_supported_status;
7777

7878
float new_timing_last_message_time_ms;
79+
80+
// returns true if instance at offset i should be included in this blend
81+
bool should_include_instance_in_blend(uint8_t i) const;
7982
};
8083

8184
#endif // AP_GPS_BLENDED_ENABLED

libraries/AP_GPS/AP_GPS_Params.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,14 @@ const AP_Param::GroupInfo AP_GPS::Params::var_info[] = {
113113
AP_GROUPINFO("CAN_OVRIDE", 9, AP_GPS::Params, override_node_id, 0),
114114
#endif
115115

116+
#if AP_GPS_BLENDED_ENABLED
117+
// @Param: BLEND_MASK
118+
// @DisplayName: Blended backend include mask
119+
// @Description: If this is a blended backend then this mask specifies which backends should be included in
120+
// @User: Advanced
121+
AP_GROUPINFO("BLEND_MASK", 9, AP_GPS::Params, blend_mask, 255),
122+
#endif
123+
116124
AP_GROUPEND
117125
};
118126

0 commit comments

Comments
 (0)