mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: rename for AHRS restructuring
This commit is contained in:
parent
e98af90749
commit
106534a654
@ -244,7 +244,7 @@ bool AP_Arming_Blimp::pre_arm_ekf_attitude_check()
|
|||||||
bool AP_Arming_Blimp::mandatory_gps_checks(bool display_failure)
|
bool AP_Arming_Blimp::mandatory_gps_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
// always check if inertial nav has started and is ready
|
// always check if inertial nav has started and is ready
|
||||||
const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
const auto &ahrs = AP::ahrs();
|
||||||
char failure_msg[50] = {};
|
char failure_msg[50] = {};
|
||||||
if (!ahrs.pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
|
if (!ahrs.pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
|
||||||
check_failed(display_failure, "AHRS: %s", failure_msg);
|
check_failed(display_failure, "AHRS: %s", failure_msg);
|
||||||
@ -363,7 +363,7 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c
|
|||||||
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Arming motors"); //MIR kept in - usually only in SITL
|
gcs().send_text(MAV_SEVERITY_INFO, "Arming motors"); //MIR kept in - usually only in SITL
|
||||||
|
|
||||||
AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
auto &ahrs = AP::ahrs();
|
||||||
|
|
||||||
blimp.initial_armed_bearing = ahrs.yaw_sensor;
|
blimp.initial_armed_bearing = ahrs.yaw_sensor;
|
||||||
|
|
||||||
@ -425,7 +425,7 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec
|
|||||||
gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors"); //MIR keeping in - usually only in SITL
|
gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors"); //MIR keeping in - usually only in SITL
|
||||||
|
|
||||||
|
|
||||||
AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
auto &ahrs = AP::ahrs();
|
||||||
|
|
||||||
// save compass offsets learned by the EKF if enabled
|
// save compass offsets learned by the EKF if enabled
|
||||||
Compass &compass = AP::compass();
|
Compass &compass = AP::compass();
|
||||||
|
@ -44,7 +44,7 @@
|
|||||||
#include <Filter/Filter.h> // Filter library
|
#include <Filter/Filter.h> // Filter library
|
||||||
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
||||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||||
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
#include <AP_InertialNav/AP_InertialNav_NavEKF.h> // ArduPilot Mega inertial navigation library
|
||||||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||||
#include <AP_Arming/AP_Arming.h>
|
#include <AP_Arming/AP_Arming.h>
|
||||||
|
@ -98,7 +98,7 @@ void Blimp::Log_Write_Attitude()
|
|||||||
// Write an EKF and POS packet
|
// Write an EKF and POS packet
|
||||||
void Blimp::Log_Write_EKF_POS()
|
void Blimp::Log_Write_EKF_POS()
|
||||||
{
|
{
|
||||||
AP::ahrs_navekf().Log_Write();
|
AP::ahrs().Log_Write();
|
||||||
ahrs.Write_AHRS2();
|
ahrs.Write_AHRS2();
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
sitl.Log_Write_SIMSTATE();
|
sitl.Log_Write_SIMSTATE();
|
||||||
|
Loading…
Reference in New Issue
Block a user