37#include <ament_index_cpp/get_package_share_directory.hpp>
38#include <boost/algorithm/string_regex.hpp>
40#include <geometry_msgs/msg/pose.hpp>
42#include <rclcpp/logger.hpp>
43#include <rclcpp/logging.hpp>
44#include <urdf_parser/urdf_parser.h>
47#include <pluginlib/class_loader.hpp>
64 const std::string& urdf_relative_path,
65 const std::string& srdf_relative_path)
67 const auto urdf_path =
68 std::filesystem::path(ament_index_cpp::get_package_share_directory(package_name)) / urdf_relative_path;
69 const auto srdf_path =
70 std::filesystem::path(ament_index_cpp::get_package_share_directory(package_name)) / srdf_relative_path;
72 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path.string());
73 if (urdf_model ==
nullptr)
78 auto srdf_model = std::make_shared<srdf::Model>();
79 if (!srdf_model->initFile(*urdf_model, srdf_path.string()))
84 return std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
91 auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf, srdf);
97 const std::string package_name =
"moveit_resources_" + robot_name +
"_description";
98 std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
99 std::string urdf_path;
100 if (robot_name ==
"pr2")
102 urdf_path = (res_path /
"urdf/robot.xml").
string();
106 urdf_path = (res_path /
"urdf" / (robot_name +
".urdf")).string();
108 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path);
109 if (urdf_model ==
nullptr)
111 RCLCPP_ERROR(getLogger(),
112 "Cannot find URDF for %s. Make sure moveit_resources_<your_robot_description> is installed",
121 auto srdf_model = std::make_shared<srdf::Model>();
122 std::string srdf_path;
123 if (robot_name ==
"pr2")
125 const std::string package_name =
"moveit_resources_" + robot_name +
"_description";
126 std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
127 srdf_path = (res_path /
"srdf/robot.xml").
string();
131 const std::string package_name =
"moveit_resources_" + robot_name +
"_moveit_config";
132 std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name));
133 srdf_path = (res_path /
"config" / (robot_name +
".srdf")).string();
135 srdf_model->initFile(*urdf_model, srdf_path);
140 const std::string& tip_link, std::string plugin,
double timeout)
142 using LoaderType = pluginlib::ClassLoader<kinematics::KinematicsBase>;
143 static std::weak_ptr<LoaderType> cached_loader;
144 std::shared_ptr<LoaderType> loader = cached_loader.lock();
147 loader = std::make_shared<LoaderType>(
"moveit_core",
"kinematics::KinematicsBase");
148 cached_loader = loader;
153 plugin =
"kdl_kinematics_plugin/KDLKinematicsPlugin";
157 kinematics::KinematicsBasePtr result = loader->createUniqueInstance(plugin);
159 result->setDefaultTimeout(timeout);
166 : urdf_model_(std::make_shared<urdf::ModelInterface>()), srdf_writer_(std::make_shared<srdf::SRDFWriter>())
168 urdf_model_->clear();
169 urdf_model_->name_ = name;
171 auto base_link = std::make_shared<urdf::Link>();
172 base_link->name = base_link_name;
173 urdf_model_->links_.insert(std::make_pair(base_link_name, base_link));
175 srdf_writer_->robot_name_ = name;
179 const std::vector<geometry_msgs::msg::Pose>& joint_origins, urdf::Vector3 joint_axis)
181 std::vector<std::string> link_names;
182 boost::split_regex(link_names, section, boost::regex(
"->"));
183 if (link_names.empty())
185 RCLCPP_ERROR(getLogger(),
"No links specified (empty section?)");
190 if (!urdf_model_->getLink(link_names[0]))
192 RCLCPP_ERROR(getLogger(),
"Link %s not present in builder yet!", link_names[0].c_str());
197 if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size())
199 RCLCPP_ERROR(getLogger(),
"There should be one more link (%zu) than there are joint origins (%zu)",
200 link_names.size(), joint_origins.size());
206 for (
size_t i = 1; i < link_names.size(); ++i)
209 if (urdf_model_->getLink(link_names[i]))
211 RCLCPP_ERROR(getLogger(),
"Link %s is already specified", link_names[i].c_str());
215 auto link = std::make_shared<urdf::Link>();
216 link->name = link_names[i];
217 urdf_model_->links_.insert(std::make_pair(link_names[i], link));
218 auto joint = std::make_shared<urdf::Joint>();
219 joint->name = link_names[i - 1] +
"-" + link_names[i] +
"-joint";
221 joint->parent_to_joint_origin_transform.clear();
222 if (!joint_origins.empty())
224 geometry_msgs::msg::Pose o = joint_origins[i - 1];
225 joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z);
226 joint->parent_to_joint_origin_transform.rotation =
227 urdf::Rotation(o.orientation.x, o.orientation.y, o.orientation.z, o.orientation.w);
230 joint->parent_link_name = link_names[i - 1];
231 joint->child_link_name = link_names[i];
232 if (type ==
"planar")
234 joint->type = urdf::Joint::PLANAR;
236 else if (type ==
"floating")
238 joint->type = urdf::Joint::FLOATING;
240 else if (type ==
"revolute")
242 joint->type = urdf::Joint::REVOLUTE;
244 else if (type ==
"continuous")
246 joint->type = urdf::Joint::CONTINUOUS;
248 else if (type ==
"prismatic")
250 joint->type = urdf::Joint::PRISMATIC;
252 else if (type ==
"fixed")
254 joint->type = urdf::Joint::FIXED;
258 RCLCPP_ERROR(getLogger(),
"No such joint type as %s", type.c_str());
263 joint->axis = joint_axis;
264 if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC)
266 auto limits = std::make_shared<urdf::JointLimits>();
267 limits->lower = -M_PI;
268 limits->upper = M_PI;
270 joint->limits = limits;
272 urdf_model_->joints_.insert(std::make_pair(joint->name, joint));
277 double ixx,
double ixy,
double ixz,
double iyy,
double iyz,
double izz)
279 if (!urdf_model_->getLink(link_name))
281 RCLCPP_ERROR(getLogger(),
"Link %s not present in builder yet!", link_name.c_str());
286 auto inertial = std::make_shared<urdf::Inertial>();
287 inertial->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
288 inertial->origin.rotation =
289 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
290 inertial->mass = mass;
298 urdf::LinkSharedPtr link;
299 urdf_model_->getLink(link_name, link);
300 link->inertial = inertial;
304 geometry_msgs::msg::Pose origin)
306 auto vis = std::make_shared<urdf::Visual>();
307 auto geometry = std::make_shared<urdf::Box>();
308 geometry->dim = urdf::Vector3(size[0], size[1], size[2]);
309 vis->geometry = geometry;
310 addLinkVisual(link_name, vis, origin);
314 geometry_msgs::msg::Pose origin)
316 if (dims.size() != 3)
318 RCLCPP_ERROR(getLogger(),
"There can only be 3 dimensions of a box (given %zu!)", dims.size());
322 auto coll = std::make_shared<urdf::Collision>();
323 auto geometry = std::make_shared<urdf::Box>();
324 geometry->dim = urdf::Vector3(dims[0], dims[1], dims[2]);
325 coll->geometry = geometry;
326 addLinkCollision(link_name, coll, origin);
330 geometry_msgs::msg::Pose origin)
332 auto coll = std::make_shared<urdf::Collision>();
333 auto geometry = std::make_shared<urdf::Mesh>();
334 geometry->filename = filename;
335 coll->geometry = geometry;
336 addLinkCollision(link_name, coll, origin);
339void RobotModelBuilder::addLinkCollision(
const std::string& link_name,
const urdf::CollisionSharedPtr& collision,
340 geometry_msgs::msg::Pose origin)
342 if (!urdf_model_->getLink(link_name))
344 RCLCPP_ERROR(getLogger(),
"Link %s not present in builder yet!", link_name.c_str());
348 collision->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
349 collision->origin.rotation =
350 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
352 urdf::LinkSharedPtr link;
353 urdf_model_->getLink(link_name, link);
354 link->collision_array.push_back(collision);
357void RobotModelBuilder::addLinkVisual(
const std::string& link_name,
const urdf::VisualSharedPtr& vis,
358 geometry_msgs::msg::Pose origin)
360 if (!urdf_model_->getLink(link_name))
362 RCLCPP_ERROR(getLogger(),
"Link %s not present in builder yet!", link_name.c_str());
366 vis->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
367 vis->origin.rotation =
368 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
370 urdf::LinkSharedPtr link;
371 urdf_model_->getLink(link_name, link);
372 if (!link->visual_array.empty())
374 link->visual_array.push_back(vis);
376 else if (link->visual)
378 link->visual_array.push_back(link->visual);
379 link->visual.reset();
380 link->visual_array.push_back(vis);
389 const std::string& type,
const std::string& name)
391 srdf::Model::VirtualJoint new_virtual_joint;
394 new_virtual_joint.name_ = parent_frame +
"-" + child_link +
"-virtual_joint";
398 new_virtual_joint.name_ = name;
400 new_virtual_joint.type_ = type;
401 new_virtual_joint.parent_frame_ = parent_frame;
402 new_virtual_joint.child_link_ = child_link;
403 srdf_writer_->virtual_joints_.push_back(new_virtual_joint);
408 srdf::Model::Group new_group;
411 new_group.name_ = base_link +
"-" + tip_link +
"-chain-group";
415 new_group.name_ = name;
417 new_group.chains_.push_back(std::make_pair(base_link, tip_link));
418 srdf_writer_->groups_.push_back(new_group);
422 const std::string& name)
424 srdf::Model::Group new_group;
425 new_group.name_ = name;
426 new_group.links_ = links;
427 new_group.joints_ = joints;
428 srdf_writer_->groups_.push_back(new_group);
432 const std::string& parent_group,
const std::string& component_group)
434 srdf::Model::EndEffector eef;
436 eef.parent_link_ = parent_link;
437 eef.parent_group_ = parent_group;
438 eef.component_group_ = component_group;
439 srdf_writer_->end_effectors_.push_back(eef);
443 const std::string& value)
445 srdf_writer_->joint_properties_[joint_name].push_back({ joint_name, property_name, value });
455 moveit::core::RobotModelPtr robot_model;
456 std::map<std::string, std::string> parent_link_tree;
457 parent_link_tree.clear();
461 urdf_model_->initTree(parent_link_tree);
463 catch (urdf::ParseError& e)
465 RCLCPP_ERROR(getLogger(),
"Failed to build tree: %s", e.what());
472 urdf_model_->initRoot(parent_link_tree);
474 catch (urdf::ParseError& e)
476 RCLCPP_ERROR(getLogger(),
"Failed to find root link: %s", e.what());
479 srdf_writer_->updateSRDFModel(*urdf_model_);
480 robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_writer_->srdf_model_);
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
void setSolverAllocators(const SolverAllocatorFn &solver, const SolverAllocatorMapFn &solver_map=SolverAllocatorMapFn())
const std::string & getName() const
Get the name of the joint group.
void addChain(const std::string §ion, const std::string &type, const std::vector< geometry_msgs::msg::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
Adds a chain of links and joints to the builder. The joint names are generated automatically as "<par...
void addInertial(const std::string &link_name, double mass, geometry_msgs::msg::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
void addEndEffector(const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="")
void addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::msg::Pose origin)
Adds a collision box to a specific link.
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
bool isValid()
Returns true if the building process so far has been valid.
void addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
Adds a new group using a list of links and a list of joints.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
void addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
Adds a virtual joint to the SRDF.
void addGroupChain(const std::string &base_link, const std::string &tip_link, const std::string &name="")
Adds a new group using a chain of links. The group is the parent joint of each link in the chain.
void addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::msg::Pose origin)
Adds a collision mesh to a specific link.
RobotModelBuilder(const std::string &name, const std::string &base_link_name)
Constructor, takes the names of the robot and the base link.
void addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::msg::Pose origin)
Adds a visual box to a specific link.
rclcpp::Logger getLogger()
std::map< const JointModelGroup *, SolverAllocatorFn > SolverAllocatorMapFn
Map from group instances to allocator functions & bijections.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
void loadIKPluginForGroup(const rclcpp::Node::SharedPtr &node, JointModelGroup *jmg, const std::string &base_link, const std::string &tip_link, std::string plugin="KDL", double timeout=0.1)
Load an IK solver plugin for the given joint model group.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.