@@ -300,17 +300,17 @@ MujocoSystemInterface::~MujocoSystemInterface()
300300 }
301301}
302302
303- hardware_interface::CallbackReturn MujocoSystemInterface::on_init (const hardware_interface::HardwareInfo& info)
303+ hardware_interface::CallbackReturn
304+ MujocoSystemInterface::on_init (const hardware_interface::HardwareComponentInterfaceParams& params)
304305{
305- if (hardware_interface::SystemInterface::on_init (info ) != hardware_interface::CallbackReturn::SUCCESS)
306+ if (hardware_interface::SystemInterface::on_init (params ) != hardware_interface::CallbackReturn::SUCCESS)
306307 {
307308 return hardware_interface::CallbackReturn::ERROR;
308309 }
309- system_info_ = info;
310310
311311 // Helper function to get parameters in hardware info.
312312 auto get_parameter = [&](const std::string& key) -> std::optional<std::string> {
313- if (auto it = info .hardware_parameters .find (key); it != info .hardware_parameters .end ())
313+ if (auto it = get_hardware_info () .hardware_parameters .find (key); it != get_hardware_info () .hardware_parameters .end ())
314314 {
315315 return it->second ;
316316 }
@@ -407,8 +407,8 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware
407407 }
408408
409409 // Pull joint and sensor information
410- register_joints (info );
411- register_sensors (info );
410+ register_joints (get_hardware_info () );
411+ register_sensors (get_hardware_info () );
412412 set_initial_pose ();
413413
414414 // Construct and start the ROS node spinning
@@ -423,12 +423,12 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware
423423 // Ready cameras
424424 RCLCPP_INFO (rclcpp::get_logger (" MujocoSystemInterface" ), " Initializing cameras..." );
425425 cameras_ = std::make_unique<MujocoCameras>(mujoco_node_, sim_mutex_, mj_data_, mj_model_, camera_publish_rate);
426- cameras_->register_cameras (info );
426+ cameras_->register_cameras (get_hardware_info () );
427427
428428 // Configure Lidar sensors
429429 RCLCPP_INFO (rclcpp::get_logger (" MujocoSystemInterface" ), " Initializing lidar..." );
430430 lidar_sensors_ = std::make_unique<MujocoLidar>(mujoco_node_, sim_mutex_, mj_data_, mj_model_, lidar_publish_rate);
431- if (!lidar_sensors_->register_lidar (info ))
431+ if (!lidar_sensors_->register_lidar (get_hardware_info () ))
432432 {
433433 RCLCPP_INFO (rclcpp::get_logger (" MujocoSystemInterface" ), " Failed to initialize lidar, exiting..." );
434434 return hardware_interface::CallbackReturn::FAILURE;
0 commit comments