From 4bafa7c75a28f37d763b1b5638f1736adc1bc11c Mon Sep 17 00:00:00 2001 From: dan-du-car Date: Fri, 28 Jul 2023 14:37:50 +0000 Subject: [PATCH] address comments --- .../CARMAStreetsPlugin/src/CARMAStreetsPlugin.h | 7 ++++++- src/v2i-hub/CDASimAdapter/src/CDASimAdapter.cpp | 10 +++++----- src/v2i-hub/CDASimAdapter/src/CDASimConnection.cpp | 8 ++++---- .../CDASimAdapter/src/include/CDASimAdapter.hpp | 2 +- .../CDASimAdapter/src/include/CDASimConnection.hpp | 2 +- .../test/TestCARMASimulationConnection.cpp | 2 +- 6 files changed, 18 insertions(+), 13 deletions(-) diff --git a/src/v2i-hub/CARMAStreetsPlugin/src/CARMAStreetsPlugin.h b/src/v2i-hub/CARMAStreetsPlugin/src/CARMAStreetsPlugin.h index 7aff1631b..9fdf4e5c7 100755 --- a/src/v2i-hub/CARMAStreetsPlugin/src/CARMAStreetsPlugin.h +++ b/src/v2i-hub/CARMAStreetsPlugin/src/CARMAStreetsPlugin.h @@ -49,7 +49,12 @@ class CARMAStreetsPlugin: public PluginClientClockAware { void HandleMobilityOperationMessage(tsm3Message &msg, routeable_message &routeableMsg); void HandleMobilityPathMessage(tsm2Message &msg, routeable_message &routeableMsg); void HandleBasicSafetyMessage(BsmMessage &msg, routeable_message &routeableMsg); - void HandleSimulatedSensorDetectedMessage(simulation::SensorDetectedObject &msg, routeable_message &routeableMsg); + /** + * @brief Handler to be invoked when the plugin received detected object, and forward the detected object to Kafka topic. + * @param msg Detected object received from TMX bus. + * @param routeableMsg routeable_message for detected object. + */ + void HandleSimulatedSensorDetectedMessage(simulation::SensorDetectedObject &msg, routeable_message &routeableMsg); /** * @brief Overide PluginClientClockAware HandleTimeSyncMessage to producer TimeSyncMessage to kafka for CARMA Streets Time Synchronization. * @param msg TimeSyncMessage received by plugin when in simulation mode. Message provides current simulation time to all processes. diff --git a/src/v2i-hub/CDASimAdapter/src/CDASimAdapter.cpp b/src/v2i-hub/CDASimAdapter/src/CDASimAdapter.cpp index b5bc7aca2..f89cb264b 100644 --- a/src/v2i-hub/CDASimAdapter/src/CDASimAdapter.cpp +++ b/src/v2i-hub/CDASimAdapter/src/CDASimAdapter.cpp @@ -91,7 +91,7 @@ namespace CDASimAdapter{ PLOG(logINFO) << "Simulation and local IP successfully initialized!"<< std::endl; uint simulation_registration_port = std::stoul(sim::get_sim_config(sim::SIMULATION_REGISTRATION_PORT)); uint time_sync_port = std::stoul(sim::get_sim_config(sim::TIME_SYNC_PORT)); - uint simulated_interaction_port = std::stoul(sim::get_sim_config(sim::SIM_INTERACTION_PORT)); + uint simulated_interaction_port =static_cast(std::stoi(sim::get_sim_config(sim::SIM_INTERACTION_PORT))); uint v2x_port = std::stoul(sim::get_sim_config(sim::V2X_PORT)); uint sim_v2x_port = std::stoul(sim::get_sim_config(sim::SIM_V2X_PORT)); std::string infrastructure_id = sim::get_sim_config(sim::INFRASTRUCTURE_ID); @@ -172,11 +172,11 @@ namespace CDASimAdapter{ PLOG(logDEBUG) << "Creating Thread Timer for simulated external object" << std::endl; try { - if(!external_bject_detection_thread_timer) + if(!external_object_detection_thread_timer) { - external_bject_detection_thread_timer = std::make_unique(); + external_object_detection_thread_timer = std::make_unique(); } - external_bject_detection_thread_timer->AddPeriodicTick([this](){ + external_object_detection_thread_timer->AddPeriodicTick([this](){ PLOG(logDEBUG1) << "Listening for Sensor Detected Message from CDASim." << std::endl; auto msg = connection->consume_sensor_detected_object_message(); if ( !msg.is_empty()) { @@ -188,7 +188,7 @@ namespace CDASimAdapter{ } }//End lambda , std::chrono::milliseconds(100)); - external_bject_detection_thread_timer->Start(); + external_object_detection_thread_timer->Start(); } catch ( const UdpServerRuntimeError &e ) { diff --git a/src/v2i-hub/CDASimAdapter/src/CDASimConnection.cpp b/src/v2i-hub/CDASimAdapter/src/CDASimConnection.cpp index fd41bb548..982ac5f64 100644 --- a/src/v2i-hub/CDASimAdapter/src/CDASimConnection.cpp +++ b/src/v2i-hub/CDASimAdapter/src/CDASimConnection.cpp @@ -132,7 +132,7 @@ namespace CDASimAdapter{ msg.set_contents( str_msg ); } else { - throw std::runtime_error("Time Sync UDP Server is not initialized"); + throw UdpServerRuntimeError("Time Sync UDP Server is not initialized"); } return msg; @@ -149,7 +149,7 @@ namespace CDASimAdapter{ } else { - throw std::runtime_error("Simulated External Object UDP Server is not initialized."); + throw UdpServerRuntimeError("Simulated External Object UDP Server is not initialized."); } return externalObj; } @@ -200,7 +200,7 @@ namespace CDASimAdapter{ return msg; } else { - throw std::runtime_error("CARMA Simulation UDP Server is not initialized!"); + throw UdpServerRuntimeError("CARMA Simulation UDP Server is not initialized!"); } return ""; @@ -212,7 +212,7 @@ namespace CDASimAdapter{ return msg; } else { - throw std::runtime_error("Immediate Forward UDP Server is not initialized!"); + throw UdpServerRuntimeError("Immediate Forward UDP Server is not initialized!"); } return ""; diff --git a/src/v2i-hub/CDASimAdapter/src/include/CDASimAdapter.hpp b/src/v2i-hub/CDASimAdapter/src/include/CDASimAdapter.hpp index 97f569db9..529cd9dc9 100644 --- a/src/v2i-hub/CDASimAdapter/src/include/CDASimAdapter.hpp +++ b/src/v2i-hub/CDASimAdapter/src/include/CDASimAdapter.hpp @@ -119,7 +119,7 @@ namespace CDASimAdapter std::unique_ptr connection; // Mutex for configuration parameter thread safety std::mutex _lock; - std::unique_ptr external_bject_detection_thread_timer; + std::unique_ptr external_object_detection_thread_timer; // Time sync thread to forward time sync messages to PluginClientClockAware V2X-Hub plugins. std::unique_ptr time_sync_timer; // Time sync thread id diff --git a/src/v2i-hub/CDASimAdapter/src/include/CDASimConnection.hpp b/src/v2i-hub/CDASimAdapter/src/include/CDASimConnection.hpp index 3f53ca368..b6bb55424 100644 --- a/src/v2i-hub/CDASimAdapter/src/include/CDASimConnection.hpp +++ b/src/v2i-hub/CDASimAdapter/src/include/CDASimConnection.hpp @@ -85,7 +85,7 @@ namespace CDASimAdapter { tmx::messages::TimeSyncMessage consume_time_sync_message() const; /** * @brief Method to consume incoming external object message. - * //To populate the simulation external object, this JSON string has to follow this specification: https://usdot-carma.atlassian.net/wiki/spaces/CRMSIM/pages/2563899417/Detected+Objects+Specification#CARMA-Street-and-V2xHub + * To populate the simulation external object, this JSON string has to follow this specification: https://usdot-carma.atlassian.net/wiki/spaces/CRMSIM/pages/2563899417/Detected+Objects+Specification#CARMA-Street-and-V2xHub * @return simulation::SensorDetectedObject. */ tmx::messages::simulation::SensorDetectedObject consume_sensor_detected_object_message() const; diff --git a/src/v2i-hub/CDASimAdapter/test/TestCARMASimulationConnection.cpp b/src/v2i-hub/CDASimAdapter/test/TestCARMASimulationConnection.cpp index 4f4c4de42..2149ce8b4 100644 --- a/src/v2i-hub/CDASimAdapter/test/TestCARMASimulationConnection.cpp +++ b/src/v2i-hub/CDASimAdapter/test/TestCARMASimulationConnection.cpp @@ -22,7 +22,7 @@ namespace CDASimAdapter { class TestCARMASimulationConnection : public ::testing::Test { protected: void SetUp() override { - // Initialize CARMA Simulation connection with (0,0,0) location and mock kafka producer. + // Initialize CARMA Simulation connection with (0,0,0) location. Point location; connection = std::make_shared("127.0.0.1", "1212", 4567, 4678, "127.0.0.1", 1213, 1214, 1215, location, sensors_file_path); }