mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Copter: use an enumeration for pre-throw motor state
This commit is contained in:
parent
bd0dff1b0e
commit
f4cbc50ba4
@ -699,7 +699,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
|
// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
|
||||||
// @Values: 0:Stopped,1:Running
|
// @Values: 0:Stopped,1:Running
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
|
GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Param: RTL_ALT_TYPE
|
// @Param: RTL_ALT_TYPE
|
||||||
|
@ -447,7 +447,7 @@ public:
|
|||||||
AP_Int16 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
|
||||||
#if MODE_THROW_ENABLED == ENABLED
|
#if MODE_THROW_ENABLED == ENABLED
|
||||||
AP_Int8 throw_motor_start;
|
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_Int8 rtl_alt_type;
|
AP_Int8 rtl_alt_type;
|
||||||
|
@ -1340,6 +1340,11 @@ public:
|
|||||||
Drop = 1
|
Drop = 1
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum class PreThrowMotorState {
|
||||||
|
STOPPED = 0,
|
||||||
|
RUNNING = 1,
|
||||||
|
};
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
const char *name() const override { return "THROW"; }
|
const char *name() const override { return "THROW"; }
|
||||||
|
@ -108,7 +108,7 @@ void ModeThrow::run()
|
|||||||
case Throw_Disarmed:
|
case Throw_Disarmed:
|
||||||
|
|
||||||
// prevent motors from rotating before the throw is detected unless enabled by the user
|
// prevent motors from rotating before the throw is detected unless enabled by the user
|
||||||
if (g.throw_motor_start == 1) {
|
if (g.throw_motor_start == PreThrowMotorState::RUNNING) {
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||||
} else {
|
} else {
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||||
@ -123,7 +123,7 @@ void ModeThrow::run()
|
|||||||
case Throw_Detecting:
|
case Throw_Detecting:
|
||||||
|
|
||||||
// prevent motors from rotating before the throw is detected unless enabled by the user
|
// prevent motors from rotating before the throw is detected unless enabled by the user
|
||||||
if (g.throw_motor_start == 1) {
|
if (g.throw_motor_start == PreThrowMotorState::RUNNING) {
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||||
} else {
|
} else {
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||||
|
Loading…
Reference in New Issue
Block a user