Skip to content

Commit

Permalink
fix(hesai_hw_monitor): merge timers to fix race condition accessing T…
Browse files Browse the repository at this point in the history
…CP driver

Signed-off-by: Max SCHMELLER <[email protected]>
  • Loading branch information
mojomex committed Apr 2, 2024
1 parent 1ae3f75 commit f8e5fd0
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,7 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp

rclcpp::TimerBase::SharedPtr diagnostics_update_timer_;
rclcpp::TimerBase::SharedPtr diagnostics_update_monitor_timer_;
rclcpp::TimerBase::SharedPtr diagnostics_status_timer_;
rclcpp::TimerBase::SharedPtr diagnostics_lidar_monitor_timer_;
rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_;
std::unique_ptr<HesaiLidarStatus> current_status;
std::unique_ptr<HesaiLidarMonitor> current_monitor;
std::unique_ptr<HesaiConfig> current_config;
Expand Down
2 changes: 1 addition & 1 deletion nebula_ros/launch/hesai_launch_all_hw.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="launch_hw" default="True" />
<arg name="launch_hw" default="true" />
<arg name="sensor_model" description="Pandar64|Pandar40P|PandarXT32|PandarXT32M|PandarAT128|PandarQT64|PandarQT128|Pandar128E4X"/>
<arg name="return_mode" default="Dual" description="See readme for supported return modes"/>
<arg name="frame_id" default="hesai"/>
Expand Down
38 changes: 20 additions & 18 deletions nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,15 +63,16 @@ HesaiHwMonitorRosWrapper::HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & o
std::static_pointer_cast<drivers::SensorConfigurationBase>(sensor_cfg_ptr));
while(hw_interface_.InitializeTcpDriver() == Status::ERROR_1)
{
RCLCPP_WARN(this->get_logger(), "Could not initialize TCP driver, retrying in 8s...");
std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000
}
std::vector<std::thread> thread_pool{};
thread_pool.emplace_back([this] {
auto result = hw_interface_.GetInventory();
current_inventory.reset(new HesaiInventory(result));
current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now()));
std::cout << "HesaiInventory" << std::endl;
std::cout << result << std::endl;
RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory");
RCLCPP_INFO_STREAM(this->get_logger(), result);
info_model = result.get_str_model();
info_serial = std::string(result.sn.begin(), result.sn.end());
hw_interface_.SetTargetModel(result.model);
Expand Down Expand Up @@ -303,29 +304,25 @@ void HesaiHwMonitorRosWrapper::InitializeHesaiDiagnostics()
current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE;
current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE;

auto on_timer_status = [this] { OnHesaiStatusTimer(); };
diagnostics_status_timer_ = std::make_shared<rclcpp::GenericTimer<decltype(on_timer_status)>>(
this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(on_timer_status),
auto fetch_diag_from_sensor = [this](){
OnHesaiStatusTimer();
if (hw_interface_.UseHttpGetLidarMonitor()) {
OnHesaiLidarMonitorTimerHttp();
} else {
OnHesaiLidarMonitorTimer();
}
};

fetch_diagnostics_timer_ = std::make_shared<rclcpp::GenericTimer<decltype(fetch_diag_from_sensor)>>(
this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor),
this->get_node_base_interface()->get_context());
this->get_node_timers_interface()->add_timer(diagnostics_status_timer_, cbg_m_);
this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_);

if (hw_interface_.UseHttpGetLidarMonitor()) {
diagnostics_updater_.add(
"hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltageHttp);
auto on_timer_lidar_monitor = [this] { OnHesaiLidarMonitorTimerHttp(); };
diagnostics_lidar_monitor_timer_ =
std::make_shared<rclcpp::GenericTimer<decltype(on_timer_lidar_monitor)>>(
this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(on_timer_lidar_monitor),
this->get_node_base_interface()->get_context());
this->get_node_timers_interface()->add_timer(diagnostics_lidar_monitor_timer_, cbg_m2_);
} else {
diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltage);
auto on_timer_lidar_monitor = [this] { OnHesaiLidarMonitorTimer(); };
diagnostics_lidar_monitor_timer_ =
std::make_shared<rclcpp::GenericTimer<decltype(on_timer_lidar_monitor)>>(
this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(on_timer_lidar_monitor),
this->get_node_base_interface()->get_context());
this->get_node_timers_interface()->add_timer(diagnostics_lidar_monitor_timer_, cbg_m2_);
}

auto on_timer_update = [this] {
Expand Down Expand Up @@ -425,6 +422,7 @@ void HesaiHwMonitorRosWrapper::OnHesaiStatusTimer()
"HesaiHwMonitorRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"),
error.what());
}
RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl);
}

void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp()
Expand All @@ -448,6 +446,8 @@ void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp()
"HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"),
error.what());
}

RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END");
}

void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer()
Expand All @@ -469,6 +469,8 @@ void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer()
"HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"),
error.what());
}

RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END");
}

void HesaiHwMonitorRosWrapper::HesaiCheckStatus(
Expand Down

0 comments on commit f8e5fd0

Please sign in to comment.