SITL: fixed segv without SITL object

This commit is contained in:
Andrew Tridgell 2019-03-01 22:06:47 +11:00
parent e00d242688
commit b1eeaa3019
1 changed files with 3 additions and 1 deletions

View File

@ -121,5 +121,7 @@ void Motor::current_and_voltage(const struct sitl_input &input, float &voltage,
current = 10 * motor_speed;
// assume 3S, and full throttle drops voltage by 0.7V
voltage = AP::sitl()->batt_voltage - motor_speed * 0.7;
if (AP::sitl()) {
voltage = AP::sitl()->batt_voltage - motor_speed * 0.7;
}
}