mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: If frame specification is FALSE, frame name is unsupported
This commit is contained in:
parent
d5e72a5440
commit
d5dd4151eb
@ -765,7 +765,6 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type)
|
|||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
// quad frame class does not support this frame type
|
// quad frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
@ -845,7 +844,6 @@ bool AP_MotorsMatrix::setup_hexa_matrix(motor_frame_type frame_type)
|
|||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
// hexa frame class does not support this frame type
|
// hexa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
|
||||||
return false;
|
return false;
|
||||||
} //hexa
|
} //hexa
|
||||||
return true;
|
return true;
|
||||||
@ -965,7 +963,6 @@ bool AP_MotorsMatrix::setup_octa_matrix(motor_frame_type frame_type)
|
|||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
// octa frame class does not support this frame type
|
// octa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
|
||||||
return false;
|
return false;
|
||||||
} // octa frame type
|
} // octa frame type
|
||||||
return true;
|
return true;
|
||||||
@ -1088,7 +1085,6 @@ bool AP_MotorsMatrix::setup_octaquad_matrix(motor_frame_type frame_type)
|
|||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
// octaquad frame class does not support this frame type
|
// octaquad frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
|
||||||
return false;
|
return false;
|
||||||
} //octaquad
|
} //octaquad
|
||||||
return true;
|
return true;
|
||||||
@ -1140,7 +1136,6 @@ bool AP_MotorsMatrix::setup_dodecahexa_matrix(motor_frame_type frame_type)
|
|||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
// dodeca-hexa frame class does not support this frame type
|
// dodeca-hexa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
|
||||||
return false;
|
return false;
|
||||||
} //dodecahexa
|
} //dodecahexa
|
||||||
return true;
|
return true;
|
||||||
@ -1293,7 +1288,6 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
#endif //AP_MOTORS_FRAME_DECA_ENABLED
|
#endif //AP_MOTORS_FRAME_DECA_ENABLED
|
||||||
default:
|
default:
|
||||||
// matrix doesn't support the configured class
|
// matrix doesn't support the configured class
|
||||||
_frame_class_string = "UNSUPPORTED";
|
|
||||||
success = false;
|
success = false;
|
||||||
_mav_type = MAV_TYPE_GENERIC;
|
_mav_type = MAV_TYPE_GENERIC;
|
||||||
break;
|
break;
|
||||||
@ -1302,6 +1296,9 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
// normalise factors to magnitude 0.5
|
// normalise factors to magnitude 0.5
|
||||||
normalise_rpy_factors();
|
normalise_rpy_factors();
|
||||||
|
|
||||||
|
if (!success) {
|
||||||
|
_frame_class_string = "UNSUPPORTED";
|
||||||
|
}
|
||||||
set_initialised_ok(success);
|
set_initialised_ok(success);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user