AP_Mount: initialise mode to default

This commit is contained in:
Randy Mackay 2015-01-15 15:29:06 +09:00 committed by Andrew Tridgell
parent ace1fd8740
commit efeb05876e
1 changed files with 2 additions and 1 deletions

View File

@ -392,9 +392,10 @@ AP_Mount::AP_Mount(const AP_AHRS &ahrs, const struct Location &current_loc) :
{
AP_Param::setup_object_defaults(this, var_info);
// initialise backend status
// initialise backend pointers and mode
for (uint8_t i=0; i<AP_MOUNT_MAX_INSTANCES; i++) {
_backends[i] = NULL;
state[i]._mode = (enum MAV_MOUNT_MODE)state[i]._default_mode.get();
}
}