mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
SITL: use AP_SIM_ENABLED define more
This commit is contained in:
parent
c58404beac
commit
f0c17f0e49
@ -18,6 +18,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#if AP_SIM_ENABLED
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "SITL.h"
|
||||
@ -343,3 +345,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // AP_SIM_ENABLED
|
||||
|
@ -471,6 +471,7 @@ void Frame::parse_vector3(picojson::value val, const char* label, Vector3f ¶
|
||||
/*
|
||||
initialise the frame
|
||||
*/
|
||||
#if AP_SIM_ENABLED
|
||||
void Frame::init(const char *frame_str, Battery *_battery)
|
||||
{
|
||||
model = default_model;
|
||||
@ -671,3 +672,4 @@ void Frame::current_and_voltage(float &voltage, float ¤t)
|
||||
current += motors[i].get_current();
|
||||
}
|
||||
}
|
||||
#endif // AP_SIM_ENABLED
|
||||
|
@ -44,7 +44,7 @@ public:
|
||||
num_motors(_num_motors),
|
||||
motors(_motors) {}
|
||||
|
||||
|
||||
#if AP_SIM_ENABLED
|
||||
// find a frame by name
|
||||
static Frame *find_frame(const char *name);
|
||||
|
||||
@ -56,7 +56,8 @@ public:
|
||||
const struct sitl_input &input,
|
||||
Vector3f &rot_accel, Vector3f &body_accel, float* rpm,
|
||||
bool use_drag=true);
|
||||
|
||||
#endif // AP_SIM_ENABLED
|
||||
|
||||
float terminal_velocity;
|
||||
float terminal_rotation_rate;
|
||||
uint8_t motor_offset;
|
||||
@ -147,8 +148,10 @@ private:
|
||||
float areaCd;
|
||||
float mass;
|
||||
float thrust_max;
|
||||
Battery *battery;
|
||||
float last_param_voltage;
|
||||
#if AP_SIM_ENABLED
|
||||
Battery *battery;
|
||||
#endif
|
||||
|
||||
// get air density in kg/m^3
|
||||
float get_air_density(float alt_amsl) const;
|
||||
|
@ -19,6 +19,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
namespace SITL {
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user