mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
SITL: Remove redundant timestep in Airsim backend
This commit is contained in:
parent
c056548f0d
commit
86a70e5797
@ -322,9 +322,6 @@ void AirSim::update(const struct sitl_input &input)
|
|||||||
{
|
{
|
||||||
send_servos(input);
|
send_servos(input);
|
||||||
recv_fdm();
|
recv_fdm();
|
||||||
// Airsim takes approximately 3ms between each message (or 333 Hz)
|
|
||||||
adjust_frame_time(1.0e6/3000);
|
|
||||||
time_advance();
|
|
||||||
|
|
||||||
// update magnetic field
|
// update magnetic field
|
||||||
update_mag_field_bf();
|
update_mag_field_bf();
|
||||||
|
Loading…
Reference in New Issue
Block a user