mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Allow switching to ACRO mode for skid steer rovers without GPS
This commit is contained in:
parent
27234f78c6
commit
572d9ba43b
@ -176,9 +176,9 @@ public:
|
|||||||
// attributes for mavlink system status reporting
|
// attributes for mavlink system status reporting
|
||||||
bool has_manual_input() const override { return true; }
|
bool has_manual_input() const override { return true; }
|
||||||
|
|
||||||
// acro mode requires a velocity estimate
|
// acro mode requires a velocity estimate for non skid-steer rovers
|
||||||
bool requires_position() const override { return false; }
|
bool requires_position() const override { return false; }
|
||||||
bool requires_velocity() const override { return true; }
|
bool requires_velocity() const override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@ -41,3 +41,8 @@ void ModeAcro::update()
|
|||||||
calc_throttle(target_speed, false);
|
calc_throttle(target_speed, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool ModeAcro::requires_velocity() const
|
||||||
|
{
|
||||||
|
return g2.motors.have_skid_steering()? false: true;
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user