mirror of https://github.com/ArduPilot/ardupilot
SITL: correct compilation when HAL_LOGGING_ENABLED is false
This commit is contained in:
parent
dae819ba54
commit
5ae4355e26
|
@ -456,6 +456,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
|||
last_speedup = sitl->speedup;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// for EKF comparison log relhome pos and velocity at loop rate
|
||||
static uint16_t last_ticks;
|
||||
uint16_t ticks = AP::scheduler().ticks();
|
||||
|
@ -482,6 +483,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
|||
airspeed_pitot,
|
||||
achieved_rate_hz/rate_hz);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// returns perpendicular height to surface downward-facing rangefinder
|
||||
|
|
|
@ -106,6 +106,7 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc,
|
|||
|
||||
Vector3f rot_T{0,0,0};
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP::logger().WriteStreaming("SFT", "TimeUS,f0,f1,f2,f3",
|
||||
"Qffff",
|
||||
AP_HAL::micros64(),
|
||||
|
@ -138,6 +139,7 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc,
|
|||
"Qfff",
|
||||
AP_HAL::micros64(),
|
||||
rot_T.x, rot_T.y, rot_T.z);
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
#if 0 //"Wobble" attempt
|
||||
rot_T.y = fin[0].Fz * radius + fin[1].Fz * radius;
|
||||
|
|
|
@ -99,6 +99,7 @@ void JSON_Master::receive(struct sitl_input &input)
|
|||
}
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
const bool use_servos = list->instance == master_instance;
|
||||
|
||||
// @LoggerMessage: SLV1
|
||||
|
@ -158,6 +159,7 @@ void JSON_Master::receive(struct sitl_input &input)
|
|||
buffer.pwm[11],
|
||||
buffer.pwm[12],
|
||||
buffer.pwm[13]);
|
||||
#endif
|
||||
|
||||
if (list->instance == master_instance) {
|
||||
// Use the servo outs from this instance
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include <sys/types.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include "pthread.h"
|
||||
#include <AP_HAL/utility/replace.h>
|
||||
|
||||
|
|
|
@ -29,7 +29,6 @@
|
|||
#include <sys/types.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include "pthread.h"
|
||||
#include <AP_HAL/utility/replace.h>
|
||||
|
||||
|
|
|
@ -1169,6 +1169,7 @@ void SIM::sim_state_send(mavlink_channel_t chan) const
|
|||
(int32_t)(state.longitude*1.0e7));
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
/* report SITL state to AP_Logger */
|
||||
void SIM::Log_Write_SIMSTATE()
|
||||
{
|
||||
|
@ -1196,6 +1197,7 @@ void SIM::Log_Write_SIMSTATE()
|
|||
};
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
convert a set of roll rates from earth frame to body frame
|
||||
|
|
Loading…
Reference in New Issue