mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
SITL: delete unused parameter 'Vector3f &body_accel' in Plane::calculate_forces()
This commit is contained in:
parent
282590668d
commit
654aea1cd1
@ -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);
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user