mirror of https://github.com/ArduPilot/ardupilot
Sub: publish filtered alt in mav msgs
This commit is contained in:
parent
4cdca46a0c
commit
e4115efa67
|
@ -380,4 +380,54 @@ void Sub::stats_update(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// get the altitude relative to the home position or the ekf origin
|
||||||
|
float Sub::get_alt_rel() const
|
||||||
|
{
|
||||||
|
if (!ap.depth_sensor_present) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// get relative position
|
||||||
|
float posD;
|
||||||
|
if (ahrs.get_relative_position_D_origin(posD)) {
|
||||||
|
if (ahrs.home_is_set()) {
|
||||||
|
// adjust to the home position
|
||||||
|
auto home = ahrs.get_home();
|
||||||
|
posD -= static_cast<float>(home.alt) * 0.01f;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// fall back to the barometer reading
|
||||||
|
posD = -AP::baro().get_altitude();
|
||||||
|
}
|
||||||
|
|
||||||
|
// convert down to up
|
||||||
|
return -posD;
|
||||||
|
}
|
||||||
|
|
||||||
|
// get the altitude above mean sea level
|
||||||
|
float Sub::get_alt_msl() const
|
||||||
|
{
|
||||||
|
if (!ap.depth_sensor_present) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
Location origin;
|
||||||
|
if (!ahrs.get_origin(origin)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// get relative position
|
||||||
|
float posD;
|
||||||
|
if (!ahrs.get_relative_position_D_origin(posD)) {
|
||||||
|
// fall back to the barometer reading
|
||||||
|
posD = -AP::baro().get_altitude();
|
||||||
|
}
|
||||||
|
|
||||||
|
// add in the ekf origin altitude
|
||||||
|
posD -= static_cast<float>(origin.alt) * 0.01f;
|
||||||
|
|
||||||
|
// convert down to up
|
||||||
|
return -posD;
|
||||||
|
}
|
||||||
|
|
||||||
AP_HAL_MAIN_CALLBACKS(&sub);
|
AP_HAL_MAIN_CALLBACKS(&sub);
|
||||||
|
|
|
@ -93,6 +93,11 @@ int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
|
||||||
return (int16_t)(sub.motors.get_throttle() * 100);
|
return (int16_t)(sub.motors.get_throttle() * 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float GCS_MAVLINK_Sub::vfr_hud_alt() const
|
||||||
|
{
|
||||||
|
return sub.get_alt_msl();
|
||||||
|
}
|
||||||
|
|
||||||
// Work around to get temperature sensor data out
|
// Work around to get temperature sensor data out
|
||||||
void GCS_MAVLINK_Sub::send_scaled_pressure3()
|
void GCS_MAVLINK_Sub::send_scaled_pressure3()
|
||||||
{
|
{
|
||||||
|
@ -842,7 +847,8 @@ uint64_t GCS_MAVLINK_Sub::capabilities() const
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet) {
|
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet)
|
||||||
|
{
|
||||||
if (packet.param1 > 0.5f) {
|
if (packet.param1 > 0.5f) {
|
||||||
sub.arming.disarm(AP_Arming::Method::TERMINATION);
|
sub.arming.disarm(AP_Arming::Method::TERMINATION);
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
@ -850,17 +856,14 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const {
|
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const
|
||||||
if (!sub.ap.depth_sensor_present) {
|
{
|
||||||
return 0;
|
return static_cast<int32_t>(sub.get_alt_msl() * 1000.0f);
|
||||||
}
|
|
||||||
return GCS_MAVLINK::global_position_int_alt();
|
|
||||||
}
|
}
|
||||||
int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const {
|
|
||||||
if (!sub.ap.depth_sensor_present) {
|
int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const
|
||||||
return 0;
|
{
|
||||||
}
|
return static_cast<int32_t>(sub.get_alt_rel() * 1000.0f);
|
||||||
return GCS_MAVLINK::global_position_int_relative_alt();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_HIGH_LATENCY2_ENABLED
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
|
|
@ -51,6 +51,7 @@ private:
|
||||||
MAV_STATE vehicle_system_status() const override;
|
MAV_STATE vehicle_system_status() const override;
|
||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
float vfr_hud_alt() const override;
|
||||||
|
|
||||||
MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
|
||||||
|
|
|
@ -426,6 +426,8 @@ private:
|
||||||
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
|
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
|
||||||
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
|
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
|
||||||
bool far_from_EKF_origin(const Location& loc);
|
bool far_from_EKF_origin(const Location& loc);
|
||||||
|
float get_alt_rel() const WARN_IF_UNUSED;
|
||||||
|
float get_alt_msl() const WARN_IF_UNUSED;
|
||||||
void exit_mission();
|
void exit_mission();
|
||||||
bool verify_loiter_unlimited();
|
bool verify_loiter_unlimited();
|
||||||
bool verify_loiter_time();
|
bool verify_loiter_time();
|
||||||
|
|
Loading…
Reference in New Issue