Skip to content

Loading Plugins at startup #35

Open
@uahic

Description

@uahic

Hi there,

I was first confused why I could not use other plugins (e.g. the ones from mujoco_ros_utils when launchin the mujoco_ro2_control_node via launch file but then had a look at the code and noted that there was no scan in the plugin dir).

My quick'n'dirty way to fix this was to simply add the code from the 'simulate' binary of Mujoco into the mujoco_ros2_control_node.cpp. It works, but the maintainer might want to solve it in a different way, potentially. So I just opened an issue instead of a PR for now.



void register_plugins() {
  // check and print plugins that are linked directly into the executable
  int nplugin = mjp_pluginCount();
  if (nplugin) {
    std::printf("Built-in plugins:\n");
    for (int i = 0; i < nplugin; ++i) {
      std::printf("    %s\n", mjp_getPluginAtSlot(i)->name);
    }
  }

  // define platform-specific strings
#if defined(_WIN32) || defined(__CYGWIN__)
  const std::string sep = "\\";
#else
  const std::string sep = "/";
#endif


  // try to open the ${EXECDIR}/MUJOCO_PLUGIN_DIR directory
  // ${EXECDIR} is the directory containing the simulate binary itself
  // MUJOCO_PLUGIN_DIR is the MUJOCO_PLUGIN_DIR preprocessor macro
  // const std::string executable_dir = getExecutableDir();
  const char* mujocoDir = std::getenv("MUJOCO_DIR");

  // Check if the environment variable is set
  if (mujocoDir == nullptr) {
      // Convert the C-string to a std::string
      std::cout << "MUJOCO_DIR is not set." << std::endl;
  }
  const std::string executable_dir(mujocoDir);
  std::cout << "MUJOCO_DIR: " << executable_dir << std::endl;

  if (executable_dir.empty()) {
    return;
  }

  const std::string plugin_dir = executable_dir + sep + "/bin" + sep + MUJOCO_PLUGIN_DIR;
  mj_loadAllPluginLibraries(
      plugin_dir.c_str(), +[](const char* filename, int first, int count) {
        std::printf("Plugins registered by library '%s':\n", filename);
        for (int i = first; i < first + count; ++i) {
          std::printf("    %s\n", mjp_getPluginAtSlot(i)->name);
        }
      });
}


// main function
int main(int argc, const char** argv) {

  rclcpp::init(argc, argv);
  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("mujoco_ros2_control_node", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));

  RCLCPP_INFO_STREAM(node->get_logger(), "Initializing mujoco_ros2_control node...");
  auto model_path = node->get_parameter("mujoco_model_path").as_string();

  register_plugins();
  ...

Metadata

Metadata

Assignees

No one assigned

    Labels

    enhancementNew feature or request

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions