mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Avoidance: correct compilation when HAL_GCS_ENABLED is false
This commit is contained in:
parent
c15a73c798
commit
93907f4a6d
@ -396,6 +396,7 @@ MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const {
|
||||
return _obstacles[_current_most_serious_threat].threat_level;
|
||||
}
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const
|
||||
{
|
||||
const mavlink_collision_t packet{
|
||||
@ -409,6 +410,7 @@ void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_
|
||||
};
|
||||
gcs().send_to_active_channels(MAVLINK_MSG_ID_COLLISION, (const char *)&packet);
|
||||
}
|
||||
#endif
|
||||
|
||||
void AP_Avoidance::handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user