SITL: allow FDM models to provide voltage, current and RPM

This commit is contained in:
Andrew Tridgell 2015-11-23 13:46:01 +11:00
parent 7a5c4ec65d
commit 223ce2b6aa
2 changed files with 8 additions and 0 deletions

View File

@ -258,6 +258,10 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) const
fdm.pitchDeg = degrees(p);
fdm.yawDeg = degrees(y);
fdm.airspeed = airspeed;
fdm.battery_voltage = battery_voltage;
fdm.battery_current = battery_current;
fdm.rpm1 = rpm1;
fdm.rpm2 = rpm2;
}
uint64_t Aircraft::get_wall_time_us() const

View File

@ -88,6 +88,10 @@ protected:
float mass; // kg
Vector3f accel_body; // m/s/s NED, body frame
float airspeed; // m/s, apparent airspeed
float battery_voltage = -1;
float battery_current = 0;
float rpm1 = 0;
float rpm2 = 0;
uint64_t time_now_us;