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 specific defines for sending of GPS mavlink messages #28572

Merged
merged 9 commits into from
Nov 13, 2024
8 changes: 7 additions & 1 deletion AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_NAV_CONTROLLER_OUTPUT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
};
Expand Down
8 changes: 7 additions & 1 deletion ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -505,10 +505,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down
8 changes: 7 additions & 1 deletion ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -630,10 +630,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down
8 changes: 7 additions & 1 deletion ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -369,10 +369,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down
8 changes: 7 additions & 1 deletion Blimp/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,10 +327,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down
8 changes: 7 additions & 1 deletion Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -541,10 +541,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down
4 changes: 3 additions & 1 deletion Tools/AP_Periph/GCS_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,10 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_MCU_STATUS,
#endif
MSG_MEMINFO,
#if AP_GPS_ENABLED
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#endif
};
Expand Down
8 changes: 5 additions & 3 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1367,6 +1367,7 @@ uint16_t AP_GPS::gps_yaw_cdeg(uint8_t instance) const
return yaw_cd;
}

#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
{
const Location &loc = location(0);
Expand Down Expand Up @@ -1400,8 +1401,9 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
0, // TODO one-sigma heading accuracy standard deviation
gps_yaw_cdeg(0));
}
#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED

#if GPS_MAX_RECEIVERS > 1
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
{
// always send the message if 2nd GPS is configured
Expand Down Expand Up @@ -1442,9 +1444,9 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
sacc * 1000, // one-sigma standard deviation in mm/s
0); // TODO one-sigma heading accuracy standard deviation
}
#endif // GPS_MAX_RECEIVERS
#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED

#if HAL_GCS_ENABLED
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
{
if (inst >= GPS_MAX_RECEIVERS) {
Expand Down
17 changes: 17 additions & 0 deletions libraries/AP_GPS/AP_GPS_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,3 +104,20 @@
#ifndef HAL_GPS_COM_PORT_DEFAULT
#define HAL_GPS_COM_PORT_DEFAULT 1
#endif


#ifndef AP_GPS_GPS_RAW_INT_SENDING_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

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

I don't think we want or need to be able to control these individually. Instead a single define AP_GPS_LEGACY_MESSAGE_SENDING_ENABLED would be a lot simpler

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I've pushed up a patch which uses the new more-details defines to save 300-odd bytes on boards that don't have either of ERB or SBF:

Board                    AP_Periph  blimp  bootloader  copter  heli  iofirmware  plane  rover  sub
CubeOrange-periph-heavy  *                                                                     
CubeRedPrimary                      *      *           *       *                 *      *      *
Durandal                            *      *           *       *                 *      *      *
Hitec-Airspeed           *                                                                     
KakuteH7-bdshot                     *      *           *       *                 *      *      *
MatekF405                           -312   *           -312    -312              -312   -320   -312
Pixhawk1-1M-bdshot                  -312               -312    -312              -312   -304   -312
f103-QiotekPeriph        *                                                                     
f303-Universal           *                                                                     
iomcu                                                                *                         
revo-mini                           -312   *           -312    -312              -312   -312   -312
skyviper-journey                                       *                                       
skyviper-v2450                                         -280                                    

Copy link
Contributor Author

Choose a reason for hiding this comment

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

.... also, if you only have a single GPS (#26751) we can save a few hundred more bytes for a year or two.

#define AP_GPS_GPS_RAW_INT_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED
#endif

#ifndef AP_GPS_GPS2_RAW_SENDING_ENABLED
#define AP_GPS_GPS2_RAW_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1
#endif

#ifndef AP_GPS_GPS_RTK_SENDING_ENABLED
#define AP_GPS_GPS_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED)
#endif

#ifndef AP_GPS_GPS2_RTK_SENDING_ENABLED
#define AP_GPS_GPS2_RTK_SENDING_ENABLED HAL_GCS_ENABLED && AP_GPS_ENABLED && GPS_MAX_RECEIVERS > 1 && (AP_GPS_SBF_ENABLED || AP_GPS_ERB_ENABLED)
#endif
5 changes: 3 additions & 2 deletions libraries/AP_GPS/GPS_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ bool AP_GPS_Backend::should_log() const
#endif


#if HAL_GCS_ENABLED
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
{
const uint8_t instance = state.instance;
Expand Down Expand Up @@ -212,7 +212,8 @@ void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
break;
}
}
#endif
#endif // AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED



/*
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_GPS/GPS_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,9 @@ class AP_GPS_Backend
#if HAL_GCS_ENABLED
//MAVLink methods
virtual bool supports_mavlink_gps_rtk_message() const { return false; }
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);
#endif
virtual void handle_msg(const mavlink_message_t &msg) { return ; }
#endif

Expand Down
26 changes: 17 additions & 9 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1030,13 +1030,17 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE},
{ MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2},
{ MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3},
#if AP_GPS_ENABLED
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
{ MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW},
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
{ MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK},
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
{ MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW},
{ MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK},
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
{ MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK},
#endif
{ MAVLINK_MSG_ID_SYSTEM_TIME, MSG_SYSTEM_TIME},
{ MAVLINK_MSG_ID_RC_CHANNELS_SCALED, MSG_SERVO_OUT},
Expand Down Expand Up @@ -6237,28 +6241,32 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
send_system_time();
break;
#if AP_GPS_ENABLED

#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
case MSG_GPS_RAW:
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
AP::gps().send_mavlink_gps_raw(chan);
break;
#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED
#if AP_GPS_GPS_RTK_SENDING_ENABLED
case MSG_GPS_RTK:
CHECK_PAYLOAD_SIZE(GPS_RTK);
AP::gps().send_mavlink_gps_rtk(chan, 0);
break;
#if GPS_MAX_RECEIVERS > 1
#endif // AP_GPS_GPS_RTK_SENDING_ENABLED
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
case MSG_GPS2_RAW:
CHECK_PAYLOAD_SIZE(GPS2_RAW);
AP::gps().send_mavlink_gps2_raw(chan);
break;
#endif
#if GPS_MAX_RECEIVERS > 1
#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
case MSG_GPS2_RTK:
CHECK_PAYLOAD_SIZE(GPS2_RTK);
AP::gps().send_mavlink_gps_rtk(chan, 1);
break;
#endif
#endif // AP_GPS_ENABLED
#endif // AP_GPS_GPS2_RTK_SENDING_ENABLED

#if AP_AHRS_ENABLED
case MSG_LOCAL_POSITION:
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
Expand Down
Loading