diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp index 788dced0d2..3ba5355e72 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.hpp @@ -77,7 +77,8 @@ class RDFLoader bool default_continuous_value = false, double default_timeout = 10.0); /** @brief Initialize the robot model from a string representation of the URDF and SRDF documents */ - RDFLoader(const std::string& urdf_string, const std::string& srdf_string); + RDFLoader(const std::string& urdf_string, const std::string& srdf_string, + const std::string& ros_name = "robot_description"); /** @brief Get the resolved parameter name for the robot description */ const std::string& getRobotDescription() const diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index de43e05744..ed25e0412a 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -87,8 +87,8 @@ RDFLoader::RDFLoader(const std::shared_ptr& node, const std::strin RCLCPP_INFO_STREAM(getLogger(), "Loaded robot model in " << (node->now() - start).seconds() << " seconds"); } -RDFLoader::RDFLoader(const std::string& urdf_string, const std::string& srdf_string) - : urdf_string_(urdf_string), srdf_string_(srdf_string) +RDFLoader::RDFLoader(const std::string& urdf_string, const std::string& srdf_string, const std::string& ros_name) + : ros_name_(ros_name), urdf_string_(urdf_string), srdf_string_(srdf_string) { if (!loadFromStrings()) {