Skip to content

Commit ab93700

Browse files
authored
feat: Update HMI status automatically (#102)
The map status is dynamically updated by updating the HMIStatus every 1 second.
1 parent 6ef2a20 commit ab93700

File tree

2 files changed

+38
-3
lines changed

2 files changed

+38
-3
lines changed

modules/dreamview/backend/hmi/hmi_worker.cc

Lines changed: 37 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -722,6 +722,7 @@ void HMIWorker::StatusUpdateThreadLoop() {
722722
while (!stop_) {
723723
std::this_thread::sleep_for(std::chrono::milliseconds(kLoopIntervalMs));
724724
UpdateComponentStatus();
725+
UpdateHMIStatus();
725726
bool status_changed = false;
726727
{
727728
WLock wlock(status_mutex_);
@@ -778,6 +779,41 @@ void HMIWorker::UpdateComponentStatus() {
778779
}
779780
}
780781

782+
void HMIWorker::UpdateHMIStatus() {
783+
constexpr double kSecondsTillTimeout(1);
784+
static double last_load_time = 0;
785+
const double now = Clock::NowInSeconds();
786+
if (now - last_load_time < kSecondsTillTimeout) {
787+
return;
788+
}
789+
790+
HMIConfig config = LoadConfig();
791+
{
792+
WLock wlock(status_mutex_);
793+
// Update UTM zone id
794+
status_.set_utm_zone_id(FLAGS_local_utm_zone_id);
795+
// Update available modes
796+
status_.clear_modes();
797+
for (const auto &iter : config.modes()) {
798+
status_.add_modes(iter.first);
799+
}
800+
// Update available maps
801+
status_.clear_maps();
802+
for (const auto &map_entry : config.maps()) {
803+
status_.add_maps(map_entry.first);
804+
}
805+
// Update available vehicles
806+
status_.clear_vehicles();
807+
for (const auto &vehicle : config.vehicles()) {
808+
status_.add_vehicles(vehicle.first);
809+
}
810+
811+
status_changed_ = true;
812+
}
813+
814+
last_load_time = now;
815+
}
816+
781817
void HMIWorker::ChangeScenarioSet(const std::string &scenario_set_id) {
782818
{
783819
RLock rlock(status_mutex_);
@@ -1313,9 +1349,7 @@ bool HMIWorker::RePlayRecord(const std::string &record_id) {
13131349
}
13141350
void HMIWorker::StopRecordPlay() {
13151351
WLock wlock(status_mutex_);
1316-
{
1317-
status_.set_current_record_id("");
1318-
}
1352+
{ status_.set_current_record_id(""); }
13191353
if (!StopModuleByCommand(FLAGS_cyber_recorder_stop_command)) {
13201354
AERROR << "stop record failed";
13211355
}

modules/dreamview/backend/hmi/hmi_worker.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,7 @@ class HMIWorker {
9797
ScenarioSet* new_scenario_set);
9898
bool UpdateDynamicModelToStatus(const std::string& dynamic_model_name);
9999
void UpdateComponentStatus();
100+
void UpdateHMIStatus();
100101
// bool UpdateRecordToStatus(const std::string& record_id,
101102
// const std::string& record_status);
102103
bool LoadRecords();

0 commit comments

Comments
 (0)