Skip to content
Snippets Groups Projects
Commit 642e5aa5 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

SITL: match simulated tilt rate for CL84 to real vehicle

parent 715db62a
No related branches found
No related tags found
No related merge requests found
......@@ -68,9 +68,9 @@ QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
if (strstr(frame_str, "cl84")) {
// setup retract servos at front
frame->motors[0].servo_type = Motor::SERVO_RETRACT;
frame->motors[0].servo_rate = 4*60.0/90; // 4 seconds to change
frame->motors[0].servo_rate = 7*60.0/90; // 7 seconds to change
frame->motors[1].servo_type = Motor::SERVO_RETRACT;
frame->motors[1].servo_rate = 4*60.0/90; // 4 seconds to change
frame->motors[1].servo_rate = 7*60.0/90; // 7 seconds to change
}
// leave first 4 servos free for plane
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment