mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
GCS_MAVLink: Always check the return value on get_velocity_NED
This commit is contained in:
parent
fcb54c2d68
commit
75caad52c0
@ -445,12 +445,10 @@ protected:
|
|||||||
virtual int32_t global_position_int_alt() const;
|
virtual int32_t global_position_int_alt() const;
|
||||||
virtual int32_t global_position_int_relative_alt() const;
|
virtual int32_t global_position_int_relative_alt() const;
|
||||||
|
|
||||||
// these methods are called after vfr_hud_velned is updated
|
|
||||||
virtual float vfr_hud_climbrate() const;
|
virtual float vfr_hud_climbrate() const;
|
||||||
virtual float vfr_hud_airspeed() const;
|
virtual float vfr_hud_airspeed() const;
|
||||||
virtual int16_t vfr_hud_throttle() const { return 0; }
|
virtual int16_t vfr_hud_throttle() const { return 0; }
|
||||||
virtual float vfr_hud_alt() const;
|
virtual float vfr_hud_alt() const;
|
||||||
Vector3f vfr_hud_velned;
|
|
||||||
|
|
||||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||||
static constexpr const float magic_force_disarm_value = 21196.0f;
|
static constexpr const float magic_force_disarm_value = 21196.0f;
|
||||||
|
@ -2460,7 +2460,11 @@ float GCS_MAVLINK::vfr_hud_airspeed() const
|
|||||||
|
|
||||||
float GCS_MAVLINK::vfr_hud_climbrate() const
|
float GCS_MAVLINK::vfr_hud_climbrate() const
|
||||||
{
|
{
|
||||||
return -vfr_hud_velned.z;
|
Vector3f velned;
|
||||||
|
if (!AP::ahrs().get_velocity_NED(velned)) {
|
||||||
|
velned.zero();
|
||||||
|
}
|
||||||
|
return -velned.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
float GCS_MAVLINK::vfr_hud_alt() const
|
float GCS_MAVLINK::vfr_hud_alt() const
|
||||||
@ -2474,7 +2478,6 @@ void GCS_MAVLINK::send_vfr_hud()
|
|||||||
|
|
||||||
// return values ignored; we send stale data
|
// return values ignored; we send stale data
|
||||||
ahrs.get_position(global_position_current_loc);
|
ahrs.get_position(global_position_current_loc);
|
||||||
ahrs.get_velocity_NED(vfr_hud_velned);
|
|
||||||
|
|
||||||
mavlink_msg_vfr_hud_send(
|
mavlink_msg_vfr_hud_send(
|
||||||
chan,
|
chan,
|
||||||
@ -3913,7 +3916,9 @@ void GCS_MAVLINK::send_global_position_int()
|
|||||||
ahrs.get_position(global_position_current_loc); // return value ignored; we send stale data
|
ahrs.get_position(global_position_current_loc); // return value ignored; we send stale data
|
||||||
|
|
||||||
Vector3f vel;
|
Vector3f vel;
|
||||||
ahrs.get_velocity_NED(vel);
|
if (!ahrs.get_velocity_NED(vel)) {
|
||||||
|
vel.zero();
|
||||||
|
}
|
||||||
|
|
||||||
mavlink_msg_global_position_int_send(
|
mavlink_msg_global_position_int_send(
|
||||||
chan,
|
chan,
|
||||||
|
Loading…
Reference in New Issue
Block a user