Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Support for GPS_STATUS mavlink msg #28517

Draft
wants to merge 7 commits into
base: master
Choose a base branch
from

Conversation

MAD-CRAZY-MAN
Copy link
Contributor

When using the ubx and NMEA protocols, satellite information is parsed and broadcasted via the GPS_STATUS MAVLink message.

I have also developed support for the SBF protocol but did not include it due to its high bandwidth requirements. However, it can be added upon request.

@MAD-CRAZY-MAN
Copy link
Contributor Author

I have verified the GPS_STATUS message in the MAVLink Inspector.

image (1)

@amilcarlucas
Copy link
Contributor

Binary Name      Text [B]         Data [B]     BSS (B)        Total Flash Change [B] (%)      Flash Free After PR (B)
---------------  ---------------  -----------  -------------  ----------------------------  -------------------------
arducopter-heli  1108 (+0.0609%)  0 (0.0000%)  -4 (-0.0015%)  1108 (+0.0608%)                                  141168
antennatracker   1580 (+0.1171%)  0 (0.0000%)  4 (+0.0015%)   1580 (+0.1169%)                                  613220
arducopter       1124 (+0.0618%)  0 (0.0000%)  -4 (-0.0015%)  1124 (+0.0616%)                                  140624
ardurover        1568 (+0.0940%)  0 (0.0000%)  0 (0.0000%)    1568 (+0.0939%)                                  294344
arduplane        2100 (+0.1156%)  0 (0.0000%)  -4 (-0.0015%)  2100 (+0.1153%)                                  143088
blimp            1668 (+0.1217%)  0 (0.0000%)  -4 (-0.0015%)  1668 (+0.1215%)                                  591104
ardusub          1636 (+0.1015%)  0 (0.0000%)  -4 (-0.0015%)  1636 (+0.1013%)                                  350004

This takes a lot of space and should therefore be behind a feature flag

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As @amilcarlucas says, please put this behind a feature flag.

Enable it by default on boards with >2048 kB of flash

@MAD-CRAZY-MAN
Copy link
Contributor Author

@peterbarker
Thank you for your review. Could you please confirm once again?

Comment on lines +1370 to +1373
void AP_GPS::send_mavlink_gps_status(mavlink_channel_t chan)
{
#if GPS_SATELITES_INFO_ENABLED
mavlink_gps_status_t msg{};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
void AP_GPS::send_mavlink_gps_status(mavlink_channel_t chan)
{
#if GPS_SATELITES_INFO_ENABLED
mavlink_gps_status_t msg{};
#if AP_GPS_SEND_MAVLINK_GPS_STATUS_ENABLED
void AP_GPS::send_mavlink_gps_status(mavlink_channel_t chan)
{
mavlink_gps_status_t msg{};
  • correct spelling of satellite
  • move compilation guards to outside of function
  • make the define name more descriptive

Comment on lines +250 to +255
uint8_t satellites_visible;
uint8_t satellites_used[20];
uint8_t satellites_elevation[20];
uint8_t satellites_azimuth[20];
uint8_t satellites_snr[20];
uint8_t satellites_prn[20];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
uint8_t satellites_visible;
uint8_t satellites_used[20];
uint8_t satellites_elevation[20];
uint8_t satellites_azimuth[20];
uint8_t satellites_snr[20];
uint8_t satellites_prn[20];
struct {
uint8_t visible;
uint8_t used[20];
uint8_t elevation[20];
uint8_t azimuth[20];
uint8_t snr[20];
uint8_t prn[20];
} satellites;

The constant 20 here is dubious; Needs to be a lot bigger than that. Also needs to be a define.

We probably want to actually dynamically allocate the structure used to hold the sv if the user asks for the information to be streamed from the autopilot.

state.satellites_visible = _gsv.num_gps + _gsv.num_glonass + _gsv.num_galileo + _gsv.num_baidou + _gsv.num_others;
}
for (int y = 0; y < end; y++) {
state.satellites_prn[y + (_gsv.this_page_num - 1) * 4] = _gsv.svid[y];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like a buffer-overflow in the making here.

Create a variable to contain the offset, constrain when it is used to actually index the array.

}
}
}
#endif
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#endif
#endif // AP_GPS_NMEA_SATELITES_INFO_ENABLED

@@ -734,6 +779,49 @@ void AP_GPS_NMEA::parse_agrica_field(uint16_t term_number, const char *term)
}
}

#if AP_GPS_NMEA_SATELITES_INFO_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#if AP_GPS_NMEA_SATELITES_INFO_ENABLED
#if AP_GPS_NMEA_SATELLITES_INFO_ENABLED

similarly elsewhere

@@ -1021,6 +1021,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_RC_CHANNELS_RAW, MSG_RC_CHANNELS_RAW},
#endif
{ MAVLINK_MSG_ID_RAW_IMU, MSG_RAW_IMU},
{ MAVLINK_MSG_ID_GPS_STATUS, MSG_GPS_STATUS},
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
{ MAVLINK_MSG_ID_GPS_STATUS, MSG_GPS_STATUS},
#if ...
{ MAVLINK_MSG_ID_GPS_STATUS, MSG_GPS_STATUS},

@@ -6339,6 +6340,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_raw_imu();
break;

case MSG_GPS_STATUS:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
case MSG_GPS_STATUS:
#if ...
case MSG_GPS_STATUS:

@@ -278,6 +278,7 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_NAV_CONTROLLER_OUTPUT,
MSG_GPS_RAW,
MSG_GPS_RTK,
MSG_GPS_STATUS,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can't stream this by default - way too much data for a normal telemetry link.

Suggested change
MSG_GPS_STATUS,

There are many ways a user could request this information from the autopilot as required - for example, a hypothetical satellites view in MissionPlanner could poke the autopilot to start sending it the data (and the autopilot would then make dynamic allocations to start collecting the data from the GPS device.

}
break;
}
state.satellites_used[i] = static_cast<uint8_t>(_buffer.sat.sat_block[i].flags & 0x01);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Again, no relevant constraint placed upon the value used to index into the array; need one.

@MAD-CRAZY-MAN MAD-CRAZY-MAN marked this pull request as draft November 8, 2024 02:06
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants