mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_Landing: stop libraries including AP_Logger.h in .h files
AP_Logger.h is a nexus of includes; while this is being improved over time, there's no reason for the library headers to include AP_Logger.h as the logger itself is access by singleton and the structures are in LogStructure.h This necessitated moving The PID_Info structure out of AP_Logger's namespace. This cleans up a pretty nasty bit - that structure is definitely not simply used for logging, but also used to pass pid information around to controllers! There are a lot of patches in here because AP_Logger.h, acting as a nexus, was providing transitive header file inclusion in many (some unlikely!) places.
This commit is contained in:
parent
6a97056736
commit
8ec0eed749
@ -408,7 +408,7 @@ bool AP_Landing::override_servos(void) {
|
||||
|
||||
// returns a PID_Info object if there is one available for the selected landing
|
||||
// type, otherwise returns a nullptr, indicating no data to be logged/sent
|
||||
const AP_Logger::PID_Info* AP_Landing::get_pid_info(void) const
|
||||
const AP_PIDInfo* AP_Landing::get_pid_info(void) const
|
||||
{
|
||||
switch (type) {
|
||||
#if HAL_LANDING_DEEPSTALL_ENABLED
|
||||
|
@ -109,7 +109,7 @@ public:
|
||||
void set_initial_slope(void) { initial_slope = slope; }
|
||||
bool is_expecting_impact(void) const;
|
||||
void Log(void) const;
|
||||
const AP_Logger::PID_Info * get_pid_info(void) const;
|
||||
const AP_PIDInfo * get_pid_info(void) const;
|
||||
|
||||
// landing altitude offset (meters)
|
||||
float alt_offset;
|
||||
|
@ -26,6 +26,7 @@
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
// table of user settable parameters for deepstall
|
||||
const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
|
||||
@ -448,13 +449,13 @@ bool AP_Landing_Deepstall::send_deepstall_message(mavlink_channel_t chan) const
|
||||
return true;
|
||||
}
|
||||
|
||||
const AP_Logger::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const
|
||||
const AP_PIDInfo& AP_Landing_Deepstall::get_pid_info(void) const
|
||||
{
|
||||
return ds_PID.get_pid_info();
|
||||
}
|
||||
|
||||
void AP_Landing_Deepstall::Log(void) const {
|
||||
const AP_Logger::PID_Info& pid_info = ds_PID.get_pid_info();
|
||||
const AP_PIDInfo& pid_info = ds_PID.get_pid_info();
|
||||
struct log_DSTL pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DSTL_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
|
@ -100,7 +100,7 @@ private:
|
||||
|
||||
bool send_deepstall_message(mavlink_channel_t chan) const;
|
||||
|
||||
const AP_Logger::PID_Info& get_pid_info(void) const;
|
||||
const AP_PIDInfo& get_pid_info(void) const;
|
||||
|
||||
//private helpers
|
||||
void build_approach_path(bool use_current_heading);
|
||||
|
@ -23,6 +23,7 @@
|
||||
#include <AP_LandingGear/AP_LandingGear.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user