mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-19 15:18:28 -04:00
SITL: add plane-redundant
This commit is contained in:
parent
a87862dd3a
commit
9fcf2b674a
@ -56,6 +56,8 @@ Plane::Plane(const char *frame_str) :
|
||||
vtail = true;
|
||||
} else if (strstr(frame_str, "-dspoilers")) {
|
||||
dspoilers = true;
|
||||
} else if (strstr(frame_str, "-redundant")) {
|
||||
redundant = true;
|
||||
}
|
||||
if (strstr(frame_str, "-elevrev")) {
|
||||
reverse_elevator_rudder = true;
|
||||
@ -311,6 +313,13 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel
|
||||
aileron = (elevon_right-elevon_left)/2;
|
||||
elevator = (elevon_left+elevon_right)/2;
|
||||
rudder = fabsf(dspoiler1_right - dspoiler2_right)/2 - fabsf(dspoiler1_left - dspoiler2_left)/2;
|
||||
} else if (redundant) {
|
||||
// channels 1/9 are left/right ailierons
|
||||
// channels 2/10 are left/right elevators
|
||||
// channels 4/12 are top/bottom rudders
|
||||
aileron = (filtered_servo_angle(input, 0) + filtered_servo_angle(input, 8)) / 2.0;
|
||||
elevator = (filtered_servo_angle(input, 1) + filtered_servo_angle(input, 9)) / 2.0;
|
||||
rudder = (filtered_servo_angle(input, 3) + filtered_servo_angle(input, 11)) / 2.0;
|
||||
}
|
||||
//printf("Aileron: %.1f elevator: %.1f rudder: %.1f\n", aileron, elevator, rudder);
|
||||
|
||||
|
@ -95,6 +95,7 @@ protected:
|
||||
bool elevons;
|
||||
bool vtail;
|
||||
bool dspoilers;
|
||||
bool redundant;
|
||||
bool reverse_elevator_rudder;
|
||||
bool ice_engine;
|
||||
bool tailsitter;
|
||||
|
Loading…
Reference in New Issue
Block a user