mirror of https://github.com/ArduPilot/ardupilot
Rover: add STICK_MIXNG param
This commit is contained in:
parent
a798f9eb27
commit
d1f7485e14
|
@ -32,13 +32,11 @@ MAV_MODE GCS_MAVLINK_Rover::base_mode() const
|
||||||
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(ENABLE_STICK_MIXING) && (ENABLE_STICK_MIXING == ENABLED) // TODO ???? Remove !
|
if (rover.g2.stick_mixing > 0 && rover.control_mode != &rover.mode_initializing) {
|
||||||
if (control_mode->stick_mixing_enabled()) {
|
|
||||||
// all modes except INITIALISING have some form of manual
|
// all modes except INITIALISING have some form of manual
|
||||||
// override if stick mixing is enabled
|
// override if stick mixing is enabled
|
||||||
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
_base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
|
_base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
|
||||||
|
|
|
@ -701,6 +701,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting),
|
AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// @Param: STICK_MIXING
|
||||||
|
// @DisplayName: Stick Mixing
|
||||||
|
// @Description: When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("STICK_MIXING", 42, ParametersG2, stick_mixing, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -397,6 +397,9 @@ public:
|
||||||
// balance both pitch trim
|
// balance both pitch trim
|
||||||
AP_Float bal_pitch_trim;
|
AP_Float bal_pitch_trim;
|
||||||
|
|
||||||
|
// stick mixing for auto modes
|
||||||
|
AP_Int8 stick_mixing;
|
||||||
|
|
||||||
#ifdef ENABLE_SCRIPTING
|
#ifdef ENABLE_SCRIPTING
|
||||||
AP_Scripting scripting;
|
AP_Scripting scripting;
|
||||||
#endif // ENABLE_SCRIPTING
|
#endif // ENABLE_SCRIPTING
|
||||||
|
|
|
@ -557,6 +557,10 @@ void Mode::calc_stopping_location(Location& stopping_loc)
|
||||||
|
|
||||||
void Mode::set_steering(float steering_value)
|
void Mode::set_steering(float steering_value)
|
||||||
{
|
{
|
||||||
|
if (allows_stick_mixing() && g2.stick_mixing > 0) {
|
||||||
|
steering_value = channel_steer->stick_mixing((int16_t)steering_value);
|
||||||
|
}
|
||||||
|
steering_value = constrain_float(steering_value, -4500.0f, 4500.0f);
|
||||||
g2.motors.set_steering(steering_value);
|
g2.motors.set_steering(steering_value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -73,6 +73,8 @@ public:
|
||||||
// returns true if vehicle can be armed or disarmed from the transmitter in this mode
|
// returns true if vehicle can be armed or disarmed from the transmitter in this mode
|
||||||
virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }
|
virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }
|
||||||
|
|
||||||
|
bool allows_stick_mixing() const { return is_autopilot_mode(); }
|
||||||
|
|
||||||
//
|
//
|
||||||
// attributes for mavlink system status reporting
|
// attributes for mavlink system status reporting
|
||||||
//
|
//
|
||||||
|
|
Loading…
Reference in New Issue