diff --git a/common/lanelet2_extension/lib/CarmaTrafficSignal.cpp b/common/lanelet2_extension/lib/CarmaTrafficSignal.cpp index 570af43cf78..a32d21bf8cf 100755 --- a/common/lanelet2_extension/lib/CarmaTrafficSignal.cpp +++ b/common/lanelet2_extension/lib/CarmaTrafficSignal.cpp @@ -119,11 +119,6 @@ boost::optional> Ca LOG_WARN_STREAM("CarmaTrafficSignal doesn't have any recorded states of traffic lights"); return boost::none; } - - if (recorded_time_stamps.size() == 1) // if only 1 timestamp recorded, this signal doesn't change - { - return std::pair(recorded_time_stamps.front().first, recorded_time_stamps.front().second); - } if (lanelet::time::toSec(fixed_cycle_duration) < 1.0) // there are recorded states, but no fixed_cycle_duration means it is dynamic { @@ -156,6 +151,7 @@ boost::optional> Ca } } + // This part of the code is used for predicting state if fixed_cycle_duration is set using setStates function // shift starting time to the future or to the past to fit input into a valid cycle boost::posix_time::time_duration accumulated_offset_duration; double offset_duration_dir = recorded_time_stamps.front().first > time_stamp ? -1.0 : 1.0; // -1 if past, +1 if time_stamp is in future