Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Avoid including AP_InertialSensor.h in headers #28933

Open
wants to merge 18 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
18 commits
Select commit Hold shift + click to select a range
b5461d4
AC_PrecLand: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
7c25d68
AP_AHRS: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
815c9f9
AP_GyroFFT: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
0c9ff58
AP_InertialSensor: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
54543f7
APM_Control: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
ae7d65e
AP_Mount: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
e99a59f
AP_NavEKF3: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
fbfc83b
AP_NMEA_Output: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
28d8dc3
AP_Soaring: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
979fb25
AP_TECS: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
775166d
AP_TempCalibration: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
551d57c
GCS_MAVLink: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
c53c01a
RC_Channel: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
aa40fd7
ArduCopter: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
0c780a8
ArduPlane: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
21bec4b
ArduSub: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
dbd5b1d
Blimp: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
aea6ba4
AP_Module: avoid including AP_InertialSensor.h in headers
peterbarker Dec 23, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
#include <AP_AHRS/AP_AHRS.h> // AHRS (Attitude Heading Reference System) interface library for ArduPilot
#include <AP_Mission/AP_Mission.h> // Mission command library
#include <AP_Mission/AP_Mission_ChangeDetector.h> // Mission command change detection library
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor Library
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
#include <SRV_Channel/SRV_Channel.h>
Expand Down
1 change: 0 additions & 1 deletion ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Mission/AP_Mission.h> // Mission command library
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library
Expand Down
2 changes: 0 additions & 2 deletions Blimp/Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,6 @@
// Application dependencies
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
// #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
// #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
#include <AP_AHRS/AP_AHRS.h>
#include <Filter/Filter.h> // Filter library
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
Expand Down
1 change: 1 addition & 0 deletions libraries/AC_PrecLand/AC_PrecLand.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

extern const AP_HAL::HAL& hal;

Expand Down
1 change: 1 addition & 0 deletions libraries/APM_Control/AP_YawController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <AP_AHRS/AP_AHRS.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

extern const AP_HAL::HAL& hal;

Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,6 +278,14 @@ void AP_AHRS::init()
#endif // AP_CUSTOMROTATIONS_ENABLED
}

const Vector3f &AP_AHRS::get_accel(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_accel(_get_primary_accel_index());
#else
return Vector3f();
#endif
}

// updates matrices responsible for rotating vectors from vehicle body
// frame to autopilot body frame from _trim variables
void AP_AHRS::update_trim_rotation_matrices()
Expand Down
4 changes: 1 addition & 3 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -619,9 +619,7 @@ class AP_AHRS {
Vector3f get_vibration(void) const;

// return primary accels
const Vector3f &get_accel(void) const {
return AP::ins().get_accel(_get_primary_accel_index());
}
const Vector3f &get_accel(void) const;

// return primary accel bias. This should be subtracted from
// get_accel() vector to get best current body frame accel
Expand Down
19 changes: 19 additions & 0 deletions libraries/AP_AHRS/AP_AHRS_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <AP_Common/Location.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
Expand All @@ -31,6 +32,24 @@ void AP_AHRS_Backend::init()
{
}

// get the index of the current primary accelerometer sensor
uint8_t AP_AHRS_Backend::get_primary_accel_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_first_usable_accel();
#else
return 0;
#endif
}

// get the index of the current primary gyro sensor
uint8_t AP_AHRS_Backend::get_primary_gyro_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_first_usable_gyro();
#else
return 0;
#endif
}

// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
Vector3f AP_AHRS::get_gyro_latest(void) const
{
Expand Down
17 changes: 2 additions & 15 deletions libraries/AP_AHRS/AP_AHRS_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <AP_Math/AP_Math.h>
#include <inttypes.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Common/Location.h>
#include <AP_NavEKF/AP_NavEKF_Source.h>

Expand Down Expand Up @@ -76,22 +75,10 @@ class AP_AHRS_Backend
virtual int8_t get_primary_core_index() const { return -1; }

// get the index of the current primary accelerometer sensor
virtual uint8_t get_primary_accel_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_first_usable_accel();
#else
return 0;
#endif
}
virtual uint8_t get_primary_accel_index(void) const;

// get the index of the current primary gyro sensor
virtual uint8_t get_primary_gyro_index(void) const {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Simply un-inlining things requires a fair amount of testing, I suggest you don't do that in this PR

#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_first_usable_gyro();
#else
return 0;
#endif
}
virtual uint8_t get_primary_gyro_index(void) const;

// Methods
virtual void update() = 0;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_AHRS/AP_AHRS_External.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

// true if the AHRS has completed initialisation
bool AP_AHRS_External::initialised(void) const
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_GyroFFT/AP_GyroFFT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
#include <AP_Motors/AP_Motors.h>
#endif
Expand Down Expand Up @@ -428,6 +429,11 @@ void AP_GyroFFT::update()
}
}

uint16_t AP_GyroFFT::get_available_samples(uint8_t axis)
{
return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available();
}

// analyse gyro data using FFT, returns number of samples still held
// called from FFT thread
uint16_t AP_GyroFFT::run_cycle()
Expand Down
7 changes: 2 additions & 5 deletions libraries/AP_GyroFFT/AP_GyroFFT.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include <AP_HAL/utility/RingBuffer.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <Filter/LowPassFilter.h>
#include <Filter/FilterWithBuffer.h>

Expand Down Expand Up @@ -221,9 +220,7 @@ class AP_GyroFFT
// whether analysis can be run again or not
bool start_analysis();
// return samples available in the gyro window
uint16_t get_available_samples(uint8_t axis) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please don't do this, this is in the hot path and inlining helps

return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available();
}
uint16_t get_available_samples(uint8_t axis);
void update_parameters(bool force);
// semaphore for access to shared FFT data
HAL_Semaphore _sem;
Expand Down Expand Up @@ -358,7 +355,7 @@ class AP_GyroFFT
AP_Int8 _num_frames;
// mask of IMUs to record gyro frames after the filter bank
AP_Int32 _options;
AP_InertialSensor* _ins;
class AP_InertialSensor* _ins;
#if DEBUG_FFT
uint32_t _last_output_ms;
EngineState _debug_state;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/FastRateBuffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
*/
#pragma once

#include "AP_InertialSensor.h"
#include "AP_InertialSensor_rate_config.h"

#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <AP_Baro/AP_Baro.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
#include <GCS_MAVLink/GCS_Dummy.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPEND
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Mount/AP_Mount_SoloGimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "AP_Mount_SoloGimbal.h"

#include "SoloGimbal.h"
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Mount/SoloGimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

#include <stdio.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>

extern const AP_HAL::HAL& hal;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <stdio.h>
#include <time.h>
#include <AP_AHRS/AP_AHRS_config.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

#if AP_AHRS_ENABLED
#include <AP_AHRS/AP_AHRS.h>
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include <AP_NavEKF/AP_NavEKF_core_common.h>
#include <AP_NavEKF/AP_NavEKF_Source.h>
#include <AP_NavEKF/EKF_Buffer.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>

#include "AP_NavEKF/EKFGSF_yaw.h"
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Soaring/Variometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
#include "Variometer.h"

#include <AP_AHRS/AP_AHRS.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>

Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) :
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <AP_Baro/AP_Baro.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Landing/AP_Landing.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

extern const AP_HAL::HAL& hal;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_TECS/AP_TECS.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <AP_Param/AP_Param.h>
#include <AP_Vehicle/AP_FixedWing.h>
#include <Filter/AverageFilter.h>
#include <Filter/LowPassFilter.h>

class AP_Landing;
class AP_TECS {
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_TempCalibration/AP_TempCalibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include "AP_TempCalibration.h"
#include <stdio.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

extern const AP_HAL::HAL& hal;

Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_TempCalibration/AP_TempCalibration.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,8 @@

#if AP_TEMPCALIBRATION_ENABLED

#include <AP_HAL/AP_HAL.h>
#include <AP_Math/vector3.h>
#include <AP_Param/AP_Param.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

class AP_TempCalibration
{
Expand Down
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/GCS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_GPS/AP_GPS.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_InertialSensor/AP_InertialSensor.h>

#include "MissionItemProtocol_Waypoints.h"
#include "MissionItemProtocol_Rally.h"
Expand Down
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Vehicle/AP_Vehicle.h>
Expand Down
1 change: 1 addition & 0 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_Generator/AP_Generator.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AP_GyroFFT/AP_GyroFFT.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
Expand Down
Loading