Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions include/mujoco_ros2_simulation/mujoco_system_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,8 @@ class MujocoSystemInterface : public hardware_interface::SystemInterface
MujocoSystemInterface();
~MujocoSystemInterface() override;

hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
hardware_interface::CallbackReturn
on_init(const hardware_interface::HardwareComponentInterfaceParams& params) override;
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;

Expand Down Expand Up @@ -153,7 +154,6 @@ class MujocoSystemInterface : public hardware_interface::SystemInterface
void publish_clock();

// System information
hardware_interface::HardwareInfo system_info_;
std::string model_path_;

// MuJoCo data pointers
Expand Down
16 changes: 8 additions & 8 deletions src/mujoco_system_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -300,17 +300,17 @@ MujocoSystemInterface::~MujocoSystemInterface()
}
}

hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware_interface::HardwareInfo& info)
hardware_interface::CallbackReturn
MujocoSystemInterface::on_init(const hardware_interface::HardwareComponentInterfaceParams& params)
{
if (hardware_interface::SystemInterface::on_init(info) != hardware_interface::CallbackReturn::SUCCESS)
if (hardware_interface::SystemInterface::on_init(params) != hardware_interface::CallbackReturn::SUCCESS)
{
return hardware_interface::CallbackReturn::ERROR;
}
system_info_ = info;

// Helper function to get parameters in hardware info.
auto get_parameter = [&](const std::string& key) -> std::optional<std::string> {
if (auto it = info.hardware_parameters.find(key); it != info.hardware_parameters.end())
if (auto it = get_hardware_info().hardware_parameters.find(key); it != get_hardware_info().hardware_parameters.end())
{
return it->second;
}
Expand Down Expand Up @@ -407,8 +407,8 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware
}

// Pull joint and sensor information
register_joints(info);
register_sensors(info);
register_joints(get_hardware_info());
register_sensors(get_hardware_info());
set_initial_pose();

// Construct and start the ROS node spinning
Expand All @@ -423,12 +423,12 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware
// Ready cameras
RCLCPP_INFO(rclcpp::get_logger("MujocoSystemInterface"), "Initializing cameras...");
cameras_ = std::make_unique<MujocoCameras>(mujoco_node_, sim_mutex_, mj_data_, mj_model_, camera_publish_rate);
cameras_->register_cameras(info);
cameras_->register_cameras(get_hardware_info());

// Configure Lidar sensors
RCLCPP_INFO(rclcpp::get_logger("MujocoSystemInterface"), "Initializing lidar...");
lidar_sensors_ = std::make_unique<MujocoLidar>(mujoco_node_, sim_mutex_, mj_data_, mj_model_, lidar_publish_rate);
if (!lidar_sensors_->register_lidar(info))
if (!lidar_sensors_->register_lidar(get_hardware_info()))
{
RCLCPP_INFO(rclcpp::get_logger("MujocoSystemInterface"), "Failed to initialize lidar, exiting...");
return hardware_interface::CallbackReturn::FAILURE;
Expand Down
Loading