mirror of https://github.com/ArduPilot/ardupilot
AR_Motors: fix have_skid_steering to return true for omni too
This commit is contained in:
parent
e06a0c6876
commit
560b2545c8
|
@ -135,7 +135,7 @@ void AP_MotorsUGV::init(uint8_t frtype)
|
||||||
setup_safety_output();
|
setup_safety_output();
|
||||||
|
|
||||||
// setup for omni vehicles
|
// setup for omni vehicles
|
||||||
if (_frame_type != FRAME_TYPE_UNDEFINED) {
|
if (is_omni()) {
|
||||||
setup_omni();
|
setup_omni();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -266,11 +266,7 @@ float AP_MotorsUGV::get_slew_limited_throttle(float throttle, float dt) const
|
||||||
*/
|
*/
|
||||||
bool AP_MotorsUGV::have_skid_steering() const
|
bool AP_MotorsUGV::have_skid_steering() const
|
||||||
{
|
{
|
||||||
if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) &&
|
return (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) && SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) || is_omni();
|
||||||
SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// true if the vehicle has a mainsail
|
// true if the vehicle has a mainsail
|
||||||
|
@ -779,8 +775,8 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott
|
||||||
// output for omni frames
|
// output for omni frames
|
||||||
void AP_MotorsUGV::output_omni(bool armed, float steering, float throttle, float lateral)
|
void AP_MotorsUGV::output_omni(bool armed, float steering, float throttle, float lateral)
|
||||||
{
|
{
|
||||||
// exit immediately if the frame type is set to UNDEFINED
|
// exit immediately if the vehicle is not omni
|
||||||
if (_frame_type == FRAME_TYPE_UNDEFINED) {
|
if (!is_omni()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -112,6 +112,9 @@ public:
|
||||||
// returns true if the configured PWM type is digital and should have fixed endpoints
|
// returns true if the configured PWM type is digital and should have fixed endpoints
|
||||||
bool is_digital_pwm_type() const;
|
bool is_digital_pwm_type() const;
|
||||||
|
|
||||||
|
// returns true if the vehicle is omni
|
||||||
|
bool is_omni() const { return _frame_type != FRAME_TYPE_UNDEFINED && _motors_num > 0; }
|
||||||
|
|
||||||
// structure for holding motor limit flags
|
// structure for holding motor limit flags
|
||||||
struct AP_MotorsUGV_limit {
|
struct AP_MotorsUGV_limit {
|
||||||
uint8_t steer_left : 1; // we have reached the steering controller's left most limit
|
uint8_t steer_left : 1; // we have reached the steering controller's left most limit
|
||||||
|
|
Loading…
Reference in New Issue