AP_Motors: init fixes for frame_class, type and initialised_ok

Thanks to OXINARF for spotting these
This commit is contained in:
Randy Mackay 2016-12-15 10:35:21 +09:00
parent 12d024e0c6
commit ffa6d1a5b9
2 changed files with 6 additions and 1 deletions

View File

@ -23,9 +23,13 @@
extern const AP_HAL::HAL& hal;
// Init
// init
void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame_type)
{
// record requested frame class and type
_last_frame_class = frame_class;
_last_frame_type = frame_type;
// setup the motors
setup_motors(frame_class, frame_type);

View File

@ -43,6 +43,7 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
// init other flags
_flags.armed = false;
_flags.interlock = false;
_flags.initialised_ok = false;
// setup throttle filtering
_throttle_filter.set_cutoff_frequency(0.0f);