diff --git a/src/estimators/heading/hdg_passthrough.cpp b/src/estimators/heading/hdg_passthrough.cpp index 2c829ef..cc8ed34 100644 --- a/src/estimators/heading/hdg_passthrough.cpp +++ b/src/estimators/heading/hdg_passthrough.cpp @@ -121,6 +121,8 @@ bool HdgPassthrough::reset(void) { } changeState(STOPPED_STATE); + // nothing to do during reset of passthrough estimator + changeState(INITIALIZED_STATE); ROS_INFO("[%s]: Estimator reset", getPrintName().c_str());