AP_Mount: initialise mode to default
This commit is contained in:
parent
ace1fd8740
commit
efeb05876e
@ -392,9 +392,10 @@ AP_Mount::AP_Mount(const AP_AHRS &ahrs, const struct Location ¤t_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();
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user