mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Windvane: move RC_IN_NO to RCx_OPTION
This commit is contained in:
parent
1e6e16e468
commit
974293ca3f
@ -35,13 +35,7 @@ const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO_FLAGS("TYPE", 1, AP_WindVane, _direction_type, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param: RC_IN_NO
|
||||
// @DisplayName: Wind vane sensor RC Input Channel
|
||||
// @Description: RC Input Channel to use as wind angle value
|
||||
// @Range: 0 16
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RC_IN_NO", 2, AP_WindVane, _rc_in_no, 0),
|
||||
// 2 was RC_IN_NO
|
||||
|
||||
// @Param: DIR_PIN
|
||||
// @DisplayName: Wind vane analog voltage pin for direction
|
||||
|
@ -98,7 +98,6 @@ private:
|
||||
|
||||
// parameters
|
||||
AP_Int8 _direction_type; // type of windvane being used
|
||||
AP_Int8 _rc_in_no; // RC input channel to use
|
||||
AP_Int8 _dir_analog_pin; // analog pin connected to wind vane direction sensor
|
||||
AP_Float _dir_analog_volt_min; // minimum voltage read by windvane
|
||||
AP_Float _dir_analog_volt_max; // maximum voltage read by windvane
|
||||
|
@ -25,8 +25,8 @@ void AP_WindVane_Home::update_direction()
|
||||
{
|
||||
float direction_apparent_ef = _frontend._home_heading;
|
||||
|
||||
if (_frontend._direction_type == _frontend.WINDVANE_PWM_PIN && _frontend._rc_in_no != 0) {
|
||||
RC_Channel *chan = rc().channel(_frontend._rc_in_no-1);
|
||||
if (_frontend._direction_type == _frontend.WINDVANE_PWM_PIN) {
|
||||
RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::WIND_VANE_DIR_OFSSET);
|
||||
if (chan != nullptr) {
|
||||
direction_apparent_ef += chan->norm_input() * radians(45);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user