mirror of https://github.com/ArduPilot/ardupilot
Rover: implement FLTMODE_GCSBLOCK bitmask
This commit is contained in:
parent
61682f6551
commit
6fafb26549
|
@ -360,6 +360,7 @@ private:
|
|||
void init_ardupilot() override;
|
||||
void startup_ground(void);
|
||||
void update_ahrs_flyforward();
|
||||
bool gcs_mode_enabled(const Mode::Number mode_num) const;
|
||||
bool set_mode(Mode &new_mode, ModeReason reason);
|
||||
bool set_mode(const uint8_t new_mode, ModeReason reason) override;
|
||||
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
|
||||
|
|
|
@ -223,6 +223,30 @@ void Rover::update_ahrs_flyforward()
|
|||
ahrs.set_fly_forward(flyforward);
|
||||
}
|
||||
|
||||
// Check if this mode can be entered from the GCS
|
||||
bool Rover::gcs_mode_enabled(const Mode::Number mode_num) const
|
||||
{
|
||||
// List of modes that can be blocked, index is bit number in parameter bitmask
|
||||
static const uint8_t mode_list [] {
|
||||
(uint8_t)Mode::Number::MANUAL,
|
||||
(uint8_t)Mode::Number::ACRO,
|
||||
(uint8_t)Mode::Number::STEERING,
|
||||
(uint8_t)Mode::Number::LOITER,
|
||||
(uint8_t)Mode::Number::FOLLOW,
|
||||
(uint8_t)Mode::Number::SIMPLE,
|
||||
(uint8_t)Mode::Number::CIRCLE,
|
||||
(uint8_t)Mode::Number::AUTO,
|
||||
(uint8_t)Mode::Number::RTL,
|
||||
(uint8_t)Mode::Number::SMART_RTL,
|
||||
(uint8_t)Mode::Number::GUIDED,
|
||||
#if MODE_DOCK_ENABLED == ENABLED
|
||||
(uint8_t)Mode::Number::DOCK
|
||||
#endif
|
||||
};
|
||||
|
||||
return !block_GCS_mode_change((uint8_t)mode_num, mode_list, ARRAY_SIZE(mode_list));
|
||||
}
|
||||
|
||||
bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
||||
{
|
||||
if (control_mode == &new_mode) {
|
||||
|
@ -230,6 +254,12 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
|||
return true;
|
||||
}
|
||||
|
||||
// Check if GCS mode change is disabled via parameter
|
||||
if ((reason == ModeReason::GCS_COMMAND) && !gcs_mode_enabled((Mode::Number)new_mode.mode_number())) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, GCS entry disabled (FLTMODE_GCSBLOCK)", new_mode.name4());
|
||||
return false;
|
||||
}
|
||||
|
||||
Mode &old_mode = *control_mode;
|
||||
if (!new_mode.enter()) {
|
||||
// Log error that we failed to enter desired flight mode
|
||||
|
|
Loading…
Reference in New Issue