From 56a6faf22347737fa8bf87dd76baee9861a0be2a Mon Sep 17 00:00:00 2001 From: Rhys Date: Wed, 22 Sep 2021 01:49:30 -0700 Subject: [PATCH] [IGN] bug fix - last controller update time should not be updated if state is not sent (#5) Signed-off-by: Rhys Mainwaring --- src/ArduPilotPlugin.cc | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/ArduPilotPlugin.cc b/src/ArduPilotPlugin.cc index e26123df..dee37c77 100755 --- a/src/ArduPilotPlugin.cc +++ b/src/ArduPilotPlugin.cc @@ -825,9 +825,8 @@ void ignition::gazebo::systems::ArduPilotPlugin::PostUpdate( double t = std::chrono::duration_cast>(_info.simTime).count(); this->SendState(t, _ecm); } + this->dataPtr->lastControllerUpdateTime = _info.simTime; } - - this->dataPtr->lastControllerUpdateTime = _info.simTime; } /////////////////////////////////////////////////