diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index d25bea6760..7ab61159cd 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -258,7 +258,7 @@ Vector3f Plane::getForce(float inputAileron, float inputElevator, float inputRud return Vector3f(ax, ay, az); } -void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel) +void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel) { float aileron = filtered_servo_angle(input, 0); float elevator = filtered_servo_angle(input, 1); @@ -380,7 +380,7 @@ void Plane::update(const struct sitl_input &input) update_wind(input); - calculate_forces(input, rot_accel, accel_body); + calculate_forces(input, rot_accel); update_dynamics(rot_accel); update_external_payload(input); diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index 4034a8d194..b5db14f3ea 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -121,7 +121,7 @@ protected: float dragCoeff(float alpha) const; Vector3f getForce(float inputAileron, float inputElevator, float inputRudder) const; Vector3f getTorque(float inputAileron, float inputElevator, float inputRudder, float inputThrust, const Vector3f &force) const; - void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel); }; } // namespace SITL diff --git a/libraries/SITL/SIM_QuadPlane.cpp b/libraries/SITL/SIM_QuadPlane.cpp index 0b99c52995..8127d0c0e7 100644 --- a/libraries/SITL/SIM_QuadPlane.cpp +++ b/libraries/SITL/SIM_QuadPlane.cpp @@ -107,7 +107,7 @@ void QuadPlane::update(const struct sitl_input &input) // first plane forces Vector3f rot_accel; - calculate_forces(input, rot_accel, accel_body); + calculate_forces(input, rot_accel); // now quad forces Vector3f quad_rot_accel;