Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/planning/rdf_loader/src/rdf_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,8 @@ RDFLoader::RDFLoader(const std::shared_ptr<rclcpp::Node>& 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())
{
Expand Down