37 #include <boost/algorithm/string_regex.hpp>
38 #include <geometry_msgs/msg/pose.hpp>
39 #include <urdf_parser/urdf_parser.h>
41 #include <ament_index_cpp/get_package_share_directory.hpp>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_utils.robot_model_test_utils");
56 auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf, srdf);
62 const std::string
package_name =
"moveit_resources_" + robot_name +
"_description";
64 std::string urdf_path;
65 if (robot_name ==
"pr2")
67 urdf_path = (res_path /
"urdf/robot.xml").
string();
71 urdf_path = (res_path /
"urdf" / (robot_name +
".urdf")).string();
73 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path);
74 if (urdf_model ==
nullptr)
76 RCLCPP_ERROR(LOGGER,
"Cannot find URDF for %s. Make sure moveit_resources_<your_robot_description> is installed",
85 auto srdf_model = std::make_shared<srdf::Model>();
86 std::string srdf_path;
87 if (robot_name ==
"pr2")
89 const std::string
package_name =
"moveit_resources_" + robot_name +
"_description";
91 srdf_path = (res_path /
"srdf/robot.xml").
string();
95 const std::string
package_name =
"moveit_resources_" + robot_name +
"_moveit_config";
97 srdf_path = (res_path /
"config" / (robot_name +
".srdf")).string();
99 srdf_model->initFile(*urdf_model, srdf_path);
104 : urdf_model_(std::make_shared<urdf::ModelInterface>()), srdf_writer_(std::make_shared<srdf::SRDFWriter>())
106 urdf_model_->clear();
107 urdf_model_->name_ =
name;
109 auto base_link = std::make_shared<urdf::Link>();
110 base_link->name = base_link_name;
111 urdf_model_->links_.insert(std::make_pair(base_link_name, base_link));
113 srdf_writer_->robot_name_ =
name;
117 const std::vector<geometry_msgs::msg::Pose>& joint_origins, urdf::Vector3 joint_axis)
119 std::vector<std::string> link_names;
120 boost::split_regex(link_names, section, boost::regex(
"->"));
121 if (link_names.empty())
123 RCLCPP_ERROR(LOGGER,
"No links specified (empty section?)");
128 if (!urdf_model_->getLink(link_names[0]))
130 RCLCPP_ERROR(LOGGER,
"Link %s not present in builder yet!", link_names[0].c_str());
135 if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size())
137 RCLCPP_ERROR(LOGGER,
"There should be one more link (%zu) than there are joint origins (%zu)", link_names.size(),
138 joint_origins.size());
144 for (
size_t i = 1; i < link_names.size(); ++i)
147 if (urdf_model_->getLink(link_names[i]))
149 RCLCPP_ERROR(LOGGER,
"Link %s is already specified", link_names[i].c_str());
153 auto link = std::make_shared<urdf::Link>();
154 link->name = link_names[i];
155 urdf_model_->links_.insert(std::make_pair(link_names[i], link));
156 auto joint = std::make_shared<urdf::Joint>();
157 joint->name = link_names[i - 1] +
"-" + link_names[i] +
"-joint";
159 joint->parent_to_joint_origin_transform.clear();
160 if (!joint_origins.empty())
162 geometry_msgs::msg::Pose o = joint_origins[i - 1];
163 joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z);
164 joint->parent_to_joint_origin_transform.rotation =
165 urdf::Rotation(o.orientation.x, o.orientation.y, o.orientation.z, o.orientation.w);
168 joint->parent_link_name = link_names[i - 1];
169 joint->child_link_name = link_names[i];
170 if (
type ==
"planar")
171 joint->type = urdf::Joint::PLANAR;
172 else if (
type ==
"floating")
173 joint->type = urdf::Joint::FLOATING;
174 else if (
type ==
"revolute")
175 joint->type = urdf::Joint::REVOLUTE;
176 else if (
type ==
"continuous")
177 joint->type = urdf::Joint::CONTINUOUS;
178 else if (
type ==
"prismatic")
179 joint->type = urdf::Joint::PRISMATIC;
180 else if (
type ==
"fixed")
184 RCLCPP_ERROR(LOGGER,
"No such joint type as %s",
type.c_str());
189 joint->axis = joint_axis;
190 if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC)
192 auto limits = std::make_shared<urdf::JointLimits>();
193 limits->lower = -M_PI;
194 limits->upper = M_PI;
196 joint->limits = limits;
198 urdf_model_->joints_.insert(std::make_pair(joint->name, joint));
203 double ixx,
double ixy,
double ixz,
double iyy,
double iyz,
double izz)
205 if (!urdf_model_->getLink(link_name))
207 RCLCPP_ERROR(LOGGER,
"Link %s not present in builder yet!", link_name.c_str());
212 auto inertial = std::make_shared<urdf::Inertial>();
213 inertial->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
214 inertial->origin.rotation =
215 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
216 inertial->mass = mass;
224 urdf::LinkSharedPtr link;
225 urdf_model_->getLink(link_name, link);
226 link->inertial = inertial;
230 geometry_msgs::msg::Pose origin)
232 auto vis = std::make_shared<urdf::Visual>();
233 auto geometry = std::make_shared<urdf::Box>();
234 geometry->dim = urdf::Vector3(size[0], size[1], size[2]);
235 vis->geometry = geometry;
236 addLinkVisual(link_name, vis, origin);
240 geometry_msgs::msg::Pose origin)
242 if (dims.size() != 3)
244 RCLCPP_ERROR(LOGGER,
"There can only be 3 dimensions of a box (given %zu!)", dims.size());
248 auto coll = std::make_shared<urdf::Collision>();
249 auto geometry = std::make_shared<urdf::Box>();
250 geometry->dim = urdf::Vector3(dims[0], dims[1], dims[2]);
251 coll->geometry = geometry;
252 addLinkCollision(link_name, coll, origin);
256 geometry_msgs::msg::Pose origin)
258 auto coll = std::make_shared<urdf::Collision>();
259 auto geometry = std::make_shared<urdf::Mesh>();
260 geometry->filename = filename;
261 coll->geometry = geometry;
262 addLinkCollision(link_name, coll, origin);
265 void RobotModelBuilder::addLinkCollision(
const std::string& link_name,
const urdf::CollisionSharedPtr& collision,
266 geometry_msgs::msg::Pose origin)
268 if (!urdf_model_->getLink(link_name))
270 RCLCPP_ERROR(LOGGER,
"Link %s not present in builder yet!", link_name.c_str());
274 collision->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
275 collision->origin.rotation =
276 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
278 urdf::LinkSharedPtr link;
279 urdf_model_->getLink(link_name, link);
280 link->collision_array.push_back(collision);
283 void RobotModelBuilder::addLinkVisual(
const std::string& link_name,
const urdf::VisualSharedPtr& vis,
284 geometry_msgs::msg::Pose origin)
286 if (!urdf_model_->getLink(link_name))
288 RCLCPP_ERROR(LOGGER,
"Link %s not present in builder yet!", link_name.c_str());
292 vis->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
293 vis->origin.rotation =
294 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
296 urdf::LinkSharedPtr link;
297 urdf_model_->getLink(link_name, link);
298 if (!link->visual_array.empty())
300 link->visual_array.push_back(vis);
302 else if (link->visual)
304 link->visual_array.push_back(link->visual);
305 link->visual.reset();
306 link->visual_array.push_back(vis);
315 const std::string&
type,
const std::string&
name)
317 srdf::Model::VirtualJoint new_virtual_joint;
319 new_virtual_joint.name_ = parent_frame +
"-" + child_link +
"-virtual_joint";
321 new_virtual_joint.name_ =
name;
322 new_virtual_joint.type_ =
type;
323 new_virtual_joint.parent_frame_ = parent_frame;
324 new_virtual_joint.child_link_ = child_link;
325 srdf_writer_->virtual_joints_.push_back(new_virtual_joint);
330 srdf::Model::Group new_group;
332 new_group.name_ = base_link +
"-" + tip_link +
"-chain-group";
334 new_group.name_ =
name;
335 new_group.chains_.push_back(std::make_pair(base_link, tip_link));
336 srdf_writer_->groups_.push_back(new_group);
340 const std::string&
name)
342 srdf::Model::Group new_group;
343 new_group.name_ =
name;
344 new_group.links_ = links;
345 new_group.joints_ = joints;
346 srdf_writer_->groups_.push_back(new_group);
350 const std::string& parent_group,
const std::string& component_group)
352 srdf::Model::EndEffector eef;
354 eef.parent_link_ = parent_link;
355 eef.parent_group_ = parent_group;
356 eef.component_group_ = component_group;
357 srdf_writer_->end_effectors_.push_back(eef);
361 const std::string& value)
363 srdf_writer_->joint_properties_[joint_name].push_back({ joint_name, property_name, value });
373 moveit::core::RobotModelPtr robot_model;
374 std::map<std::string, std::string> parent_link_tree;
375 parent_link_tree.clear();
379 urdf_model_->initTree(parent_link_tree);
381 catch (urdf::ParseError& e)
383 RCLCPP_ERROR(LOGGER,
"Failed to build tree: %s", e.what());
390 urdf_model_->initRoot(parent_link_tree);
392 catch (urdf::ParseError& e)
394 RCLCPP_ERROR(LOGGER,
"Failed to find root link: %s", e.what());
397 srdf_writer_->updateSRDFModel(*urdf_model_);
398 robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_writer_->srdf_model_);
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.
def get_package_share_directory(pkg_name)
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.