mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: add specific defines for sending of GPS mavlink messages
This commit is contained in:
parent
19bce3b171
commit
199074ce34
|
@ -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);
|
||||
|
@ -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
|
||||
|
@ -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) {
|
||||
|
|
|
@ -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
|
||||
#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
|
||||
#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
|
||||
#endif
|
||||
|
|
|
@ -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;
|
||||
|
@ -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
|
||||
|
||||
|
||||
|
||||
/*
|
||||
|
|
|
@ -71,7 +71,9 @@ public:
|
|||
#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
|
||||
|
||||
|
|
Loading…
Reference in New Issue