41#if __has_include(<urdf/model.hpp>)
42#include <urdf/model.hpp>
44#include <urdf/model.h>
46#include <srdfdom/model.h>
47#include <rclcpp/rclcpp.hpp>
76 RDFLoader(
const std::shared_ptr<rclcpp::Node>& node,
const std::string& ros_name =
"robot_description",
77 bool default_continuous_value =
false,
double default_timeout = 10.0);
80 RDFLoader(
const std::string& urdf_string,
const std::string& srdf_string);
95 const urdf::ModelInterfaceSharedPtr&
getURDF()
const
119 const std::vector<std::string>& xacro_args);
124 const std::vector<std::string>& xacro_args);
128 const std::string& relative_path,
const std::vector<std::string>& xacro_args);
131 bool loadFromStrings();
133 void urdfUpdateCallback(
const std::string& new_urdf_string);
134 void srdfUpdateCallback(
const std::string& new_srdf_string);
138 std::string ros_name_;
139 std::string urdf_string_, srdf_string_;
144 srdf::ModelSharedPtr srdf_;
145 urdf::ModelInterfaceSharedPtr urdf_;
#define MOVEIT_CLASS_FORWARD(C)
static bool loadXmlFileToString(std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args)
helper that branches between loadFileToString() and loadXacroFileToString() based on result of isXacr...
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
void setNewModelCallback(const NewModelCallback &cb)
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
static bool loadPkgFileToString(std::string &buffer, const std::string &package_name, const std::string &relative_path, const std::vector< std::string > &xacro_args)
helper that generates a file path based on package name and relative file path to package
const std::string & getURDFString() const
Get the URDF string.
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
static bool loadFileToString(std::string &buffer, const std::string &path)
load file from given path into buffer
static bool loadXacroFileToString(std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args)
run xacro with the given args on the file, return result in buffer
SynchronizedStringParameter is a way to load a string from the ROS environment.
std::function< void()> NewModelCallback