39 #include <std_msgs/msg/string.hpp>
40 #include <ament_index_cpp/get_package_prefix.hpp>
41 #include <ament_index_cpp/get_package_share_directory.hpp>
43 #include <rclcpp/duration.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/node.hpp>
47 #include <rclcpp/time.hpp>
58 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_rdf_loader.rdf_loader");
61 bool default_continuous_value,
double default_timeout)
64 auto start = node->now();
67 node, ros_name, [
this](
const std::string& new_urdf_string) {
return urdfUpdateCallback(new_urdf_string); },
68 default_continuous_value, default_timeout);
70 const std::string srdf_name = ros_name +
"_semantic";
72 node, srdf_name, [
this](
const std::string& new_srdf_string) {
return srdfUpdateCallback(new_srdf_string); },
73 default_continuous_value, default_timeout);
75 if (!loadFromStrings())
80 RCLCPP_INFO_STREAM(LOGGER,
"Loaded robot model in " << (node->now() - start).seconds() <<
" seconds");
84 : urdf_string_(urdf_string), srdf_string_(srdf_string)
86 if (!loadFromStrings())
92 bool RDFLoader::loadFromStrings()
94 std::unique_ptr<urdf::Model> urdf = std::make_unique<urdf::Model>();
95 if (!urdf->initString(urdf_string_))
97 RCLCPP_INFO(LOGGER,
"Unable to parse URDF");
101 srdf::ModelSharedPtr srdf = std::make_shared<srdf::Model>();
102 if (!srdf->initString(*urdf, srdf_string_))
104 RCLCPP_ERROR(LOGGER,
"Unable to parse SRDF");
108 urdf_ = std::move(urdf);
109 srdf_ = std::move(srdf);
115 std::string lower_path = path;
116 std::transform(lower_path.begin(), lower_path.end(), lower_path.begin(), ::tolower);
118 return lower_path.find(
".xacro") != std::string::npos;
125 RCLCPP_ERROR(LOGGER,
"Path is empty");
129 if (!std::filesystem::exists(path))
131 RCLCPP_ERROR(LOGGER,
"File does not exist");
135 std::ifstream stream(path.c_str());
138 RCLCPP_ERROR(LOGGER,
"Unable to load path");
143 stream.seekg(0, std::ios::end);
144 buffer.reserve(stream.tellg());
145 stream.seekg(0, std::ios::beg);
146 buffer.assign((std::istreambuf_iterator<char>(stream)), std::istreambuf_iterator<char>());
153 const std::vector<std::string>& xacro_args)
158 RCLCPP_ERROR(LOGGER,
"Path is empty");
162 if (!std::filesystem::exists(path))
164 RCLCPP_ERROR(LOGGER,
"File does not exist");
168 std::string cmd =
"ros2 run xacro xacro ";
169 for (
const std::string& xacro_arg : xacro_args)
170 cmd += xacro_arg +
" ";
174 FILE* pipe = _popen(cmd.c_str(),
"r");
176 FILE* pipe = popen(cmd.c_str(),
"r");
180 RCLCPP_ERROR(LOGGER,
"Unable to load path");
184 char pipe_buffer[128];
187 if (fgets(pipe_buffer, 128, pipe) !=
nullptr)
188 buffer += pipe_buffer;
200 const std::vector<std::string>& xacro_args)
211 const std::string& relative_path,
const std::vector<std::string>& xacro_args)
213 std::string package_path;
218 catch (
const ament_index_cpp::PackageNotFoundError& e)
220 RCLCPP_ERROR(LOGGER,
"ament_index_cpp: %s", e.what());
224 std::filesystem::path path(package_path);
225 path = path / relative_path;
230 void RDFLoader::urdfUpdateCallback(
const std::string& new_urdf_string)
232 urdf_string_ = new_urdf_string;
233 if (!loadFromStrings())
243 void RDFLoader::srdfUpdateCallback(
const std::string& new_srdf_string)
245 srdf_string_ = new_srdf_string;
246 if (!loadFromStrings())
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
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
RDFLoader(const std::shared_ptr< rclcpp::Node > &node, const std::string &ros_name="robot_description", bool default_continuous_value=false, double default_timeout=10.0)
Default constructor.
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
std::string loadInitialValue(const std::shared_ptr< rclcpp::Node > &node, const std::string &name, const StringCallback &parent_callback={}, bool default_continuous_value=false, double default_timeout=10.0)
def get_package_share_directory(pkg_name)
const rclcpp::Logger LOGGER