AP_Motors: Add motor test checks method to refuse test
This commit is contained in:
parent
c5733e7634
commit
d57ce2ad6f
@ -618,6 +618,13 @@ bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Tell user motor test is disabled on heli
|
||||||
|
bool AP_MotorsHeli::motor_test_checks(size_t buflen, char *buffer) const
|
||||||
|
{
|
||||||
|
hal.util->snprintf(buffer, buflen, "Disabled on heli");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
||||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||||
uint32_t AP_MotorsHeli::get_motor_mask()
|
uint32_t AP_MotorsHeli::get_motor_mask()
|
||||||
|
@ -159,6 +159,9 @@ public:
|
|||||||
// Run arming checks
|
// Run arming checks
|
||||||
bool arming_checks(size_t buflen, char *buffer) const override;
|
bool arming_checks(size_t buflen, char *buffer) const override;
|
||||||
|
|
||||||
|
// Tell user motor test is disabled on heli
|
||||||
|
bool motor_test_checks(size_t buflen, char *buffer) const override;
|
||||||
|
|
||||||
// output_test_seq - disabled on heli, do nothing
|
// output_test_seq - disabled on heli, do nothing
|
||||||
void _output_test_seq(uint8_t motor_seq, int16_t pwm) override {};
|
void _output_test_seq(uint8_t motor_seq, int16_t pwm) override {};
|
||||||
|
|
||||||
|
@ -293,6 +293,14 @@ bool AP_Motors::arming_checks(size_t buflen, char *buffer) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Motors::motor_test_checks(size_t buflen, char *buffer) const
|
||||||
|
{
|
||||||
|
// Must pass base class arming checks (the function above)
|
||||||
|
// Do not run frame specific arming checks as motor test is less strict
|
||||||
|
// For example not all the outputs have to be assigned
|
||||||
|
return AP_Motors::arming_checks(buflen, buffer);
|
||||||
|
}
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
AP_Motors *motors()
|
AP_Motors *motors()
|
||||||
{
|
{
|
||||||
|
@ -111,6 +111,7 @@ public:
|
|||||||
|
|
||||||
// check initialisation succeeded
|
// check initialisation succeeded
|
||||||
virtual bool arming_checks(size_t buflen, char *buffer) const;
|
virtual bool arming_checks(size_t buflen, char *buffer) const;
|
||||||
|
virtual bool motor_test_checks(size_t buflen, char *buffer) const;
|
||||||
bool initialised_ok() const { return _initialised_ok; }
|
bool initialised_ok() const { return _initialised_ok; }
|
||||||
void set_initialised_ok(bool val) { _initialised_ok = val; }
|
void set_initialised_ok(bool val) { _initialised_ok = val; }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user