mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Landing: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
97c8d149f7
commit
a5ccb1d312
@ -625,6 +625,7 @@ bool AP_Landing::is_complete(void) const
|
|||||||
|
|
||||||
void AP_Landing::Log(void) const
|
void AP_Landing::Log(void) const
|
||||||
{
|
{
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
switch (type) {
|
switch (type) {
|
||||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||||
type_slope_log();
|
type_slope_log();
|
||||||
@ -637,6 +638,7 @@ void AP_Landing::Log(void) const
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -456,6 +456,7 @@ const AP_PIDInfo& AP_Landing_Deepstall::get_pid_info(void) const
|
|||||||
return ds_PID.get_pid_info();
|
return ds_PID.get_pid_info();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_Landing_Deepstall::Log(void) const {
|
void AP_Landing_Deepstall::Log(void) const {
|
||||||
const AP_PIDInfo& pid_info = ds_PID.get_pid_info();
|
const AP_PIDInfo& pid_info = ds_PID.get_pid_info();
|
||||||
struct log_DSTL pkt = {
|
struct log_DSTL pkt = {
|
||||||
@ -479,6 +480,7 @@ void AP_Landing_Deepstall::Log(void) const {
|
|||||||
};
|
};
|
||||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// termination handling, expected to set the servo outputs
|
// termination handling, expected to set the servo outputs
|
||||||
bool AP_Landing_Deepstall::terminate(void) {
|
bool AP_Landing_Deepstall::terminate(void) {
|
||||||
|
@ -407,6 +407,7 @@ bool AP_Landing::type_slope_is_complete(void) const
|
|||||||
return (type_slope_stage == SlopeStage::FINAL);
|
return (type_slope_stage == SlopeStage::FINAL);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_Landing::type_slope_log(void) const
|
void AP_Landing::type_slope_log(void) const
|
||||||
{
|
{
|
||||||
// @LoggerMessage: LAND
|
// @LoggerMessage: LAND
|
||||||
@ -429,6 +430,7 @@ void AP_Landing::type_slope_log(void) const
|
|||||||
(double)alt_offset,
|
(double)alt_offset,
|
||||||
(double)height_flare_log);
|
(double)height_flare_log);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
bool AP_Landing::type_slope_is_throttle_suppressed(void) const
|
bool AP_Landing::type_slope_is_throttle_suppressed(void) const
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user