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>
44#include <rclcpp/duration.hpp>
45#include <rclcpp/logger.hpp>
46#include <rclcpp/logging.hpp>
47#include <rclcpp/node.hpp>
48#include <rclcpp/time.hpp>
68 bool default_continuous_value,
double default_timeout)
71 auto start = node->now();
74 node, ros_name, [
this](
const std::string& new_urdf_string) {
return urdfUpdateCallback(new_urdf_string); },
75 default_continuous_value, default_timeout);
77 const std::string srdf_name = ros_name +
"_semantic";
79 node, srdf_name, [
this](
const std::string& new_srdf_string) {
return srdfUpdateCallback(new_srdf_string); },
80 default_continuous_value, default_timeout);
82 if (!loadFromStrings())
87 RCLCPP_INFO_STREAM(getLogger(),
"Loaded robot model in " << (node->now() - start).seconds() <<
" seconds");
91 : urdf_string_(urdf_string), srdf_string_(srdf_string)
93 if (!loadFromStrings())
99bool RDFLoader::loadFromStrings()
101 std::unique_ptr<urdf::Model> urdf = std::make_unique<urdf::Model>();
102 if (!urdf->initString(urdf_string_))
104 RCLCPP_INFO(getLogger(),
"Unable to parse URDF");
108 srdf::ModelSharedPtr srdf = std::make_shared<srdf::Model>();
109 if (!srdf->initString(*urdf, srdf_string_))
111 RCLCPP_ERROR(getLogger(),
"Unable to parse SRDF");
115 urdf_ = std::move(urdf);
116 srdf_ = std::move(srdf);
122 std::string lower_path = path;
123 std::transform(lower_path.begin(), lower_path.end(), lower_path.begin(), ::tolower);
125 return lower_path.find(
".xacro") != std::string::npos;
132 RCLCPP_ERROR(getLogger(),
"Path is empty");
136 if (!std::filesystem::exists(path))
138 RCLCPP_ERROR(getLogger(),
"File does not exist");
142 std::ifstream stream(path.c_str());
145 RCLCPP_ERROR(getLogger(),
"Unable to load path");
150 stream.seekg(0, std::ios::end);
151 buffer.reserve(stream.tellg());
152 stream.seekg(0, std::ios::beg);
153 buffer.assign((std::istreambuf_iterator<char>(stream)), std::istreambuf_iterator<char>());
160 const std::vector<std::string>& xacro_args)
165 RCLCPP_ERROR(getLogger(),
"Path is empty");
169 if (!std::filesystem::exists(path))
171 RCLCPP_ERROR(getLogger(),
"File does not exist");
175 std::string cmd =
"ros2 run xacro xacro ";
176 for (
const std::string& xacro_arg : xacro_args)
177 cmd += xacro_arg +
" ";
181 FILE* pipe = _popen(cmd.c_str(),
"r");
183 FILE* pipe = popen(cmd.c_str(),
"r");
187 RCLCPP_ERROR(getLogger(),
"Unable to load path");
191 char pipe_buffer[128];
194 if (fgets(pipe_buffer, 128, pipe) !=
nullptr)
195 buffer += pipe_buffer;
207 const std::vector<std::string>& xacro_args)
218 const std::string& relative_path,
const std::vector<std::string>& xacro_args)
220 std::string package_path;
223 package_path = ament_index_cpp::get_package_share_directory(package_name);
225 catch (
const ament_index_cpp::PackageNotFoundError& e)
227 RCLCPP_ERROR(getLogger(),
"ament_index_cpp: %s", e.what());
231 std::filesystem::path path(package_path);
232 path = path / relative_path;
237void RDFLoader::urdfUpdateCallback(
const std::string& new_urdf_string)
239 urdf_string_ = new_urdf_string;
240 if (!loadFromStrings())
250void RDFLoader::srdfUpdateCallback(
const std::string& new_srdf_string)
252 srdf_string_ = new_srdf_string;
253 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)
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.