Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_ServoRelayEvents: allow mavlink command of rcin scaled functions #25241

Merged
merged 2 commits into from
Oct 16, 2023

Conversation

tpwrules
Copy link
Contributor

@tpwrules tpwrules commented Oct 12, 2023

Allow MAV_CMD_DO_SET_SERVO and MAV_CMD_DO_REPEAT_SERVO to be used on
a servo output set to an RCINnScaled function (i.e. k_rcinN_mapped).

Scaling is applied so that a commanded servo PWM of <=1000 maps to
SERVOn_MIN, a PWM of 1500 maps to SERVOn_TRIM, and a PWM of >=2000 maps to
SERVOn_MAX. Linear interpolation is performed between ranges.

This allows control of servos/hardware with reasonable/safe scaling applied by firmware and allows more functionality from mission scripts.

In our use case we have a variable aperture controlled by a hobby servo for releasing crop seeds. The scaling is controlled by the mechanical geometry and programmed in the autopilot firmware so that SERVOn_MIN is fully closed and SERVOn_MAX is fully open. By setting the servo function to an RC scaled value, we can have straightforward controls from both an RC controller programmed to send 1000-2000 on a knob and mission scripts with that same range without danger of going overrange and damaging the mechanism or servo. This concept should extend logically to many other types of actuators one may wish to attach which don't fall under e.g. camera or sprayer headings.

Tested on SITL (on top of master) and on a real copter (on top of Copter-4.4.1).

Allow other modules to get and store the PWM value for a specific scaled
value and re-apply it later.
Allow `MAV_CMD_DO_SET_SERVO` and `MAV_CMD_DO_REPEAT_SERVO` to be used on
a servo output set to an RCINnScaled function (i.e. k_rcinN_mapped).

Scaling is applied so that a commanded servo PWM of <=1000 maps to
SERVOn_MIN, a PWM of 1500 maps to SERVOn_TRIM, and a PWM of >=2000 maps to
SERVOn_MAX. Linear interpolation is performed between ranges.
// mapped channels are set up with a -/+ 4500 angle range by
// SRV_Channel::aux_servo_function_setup
int16_t angle_scaled = constrain_uint16(pwm, 1000, 2000);
angle_scaled = (angle_scaled - 1500) * 9; // 1000 ... 2000 -> -500 ... 500 -> -4500 ... 4500
Copy link
Member

@IamPete1 IamPete1 Oct 16, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
angle_scaled = (angle_scaled - 1500) * 9; // 1000 ... 2000 -> -500 ... 500 -> -4500 ... 4500
angle_scaled = (angle_scaled - 1500) * (4500/500); // 1000 ... 2000 -> -500 ... 500 -> -4500 ... 4500

The compiler will evaluate it to 9 in any case and I think this makes it a little easier to understand.

@tridge tridge merged commit fa31a5e into ArduPilot:master Oct 16, 2023
@tpwrules tpwrules deleted the mavlink-rc-scaled branch October 16, 2023 23:55
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants