38 #include <boost/algorithm/string_regex.hpp>
39 #include <boost/math/constants/constants.hpp>
40 #include <geometry_msgs/Pose.h>
42 #include <urdf_parser/urdf_parser.h>
51 const std::string
LOGNAME =
"robot_model_builder";
58 return moveit::core::RobotModelPtr();
59 return std::make_shared<moveit::core::RobotModel>(
urdf,
srdf);
64 std::string urdf_path;
65 if (robot_name ==
"pr2")
72 ros::package::getPath(
"moveit_resources_" + robot_name +
"_description") +
"/urdf/" + robot_name +
".urdf";
74 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDFFile(urdf_path);
75 if (urdf_model ==
nullptr)
77 ROS_ERROR_NAMED(
LOGNAME,
"Cannot find URDF for %s. Make sure moveit_resources/your robot description is installed",
86 auto srdf_model = std::make_shared<srdf::Model>();
87 std::string srdf_path;
88 if (robot_name ==
"pr2")
95 ros::package::getPath(
"moveit_resources_" + robot_name +
"_moveit_config") +
"/config/" + robot_name +
".srdf";
97 srdf_model->initFile(*urdf_model, srdf_path);
101 void loadIKPluginForGroup(JointModelGroup* jmg,
const std::string& base_link,
const std::string& tip_link,
102 std::string plugin,
double timeout)
105 static std::weak_ptr<LoaderType> cached_loader;
106 std::shared_ptr<LoaderType> loader = cached_loader.lock();
109 loader = std::make_shared<LoaderType>(
"moveit_core",
"kinematics::KinematicsBase");
110 cached_loader = loader;
115 plugin =
"kdl_kinematics_plugin/KDLKinematicsPlugin";
117 jmg->setSolverAllocators(
119 kinematics::KinematicsBasePtr result = loader->createUniqueInstance(plugin);
121 result->setDefaultTimeout(timeout);
128 : urdf_model_(new
urdf::ModelInterface()), srdf_writer_(new
srdf::SRDFWriter())
130 urdf_model_->clear();
131 urdf_model_->name_ =
name;
133 auto base_link = std::make_shared<urdf::Link>();
134 base_link->name = base_link_name;
135 urdf_model_->links_.insert(std::make_pair(base_link_name, base_link));
137 srdf_writer_->robot_name_ =
name;
140 RobotModelBuilder& RobotModelBuilder::addChain(
const std::string& section,
const std::string& type,
141 const std::vector<geometry_msgs::Pose>& joint_origins,
142 urdf::Vector3 joint_axis)
144 std::vector<std::string> link_names;
145 boost::split_regex(link_names, section, boost::regex(
"->"));
146 if (link_names.empty())
153 if (!urdf_model_->getLink(link_names[0]))
160 if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size())
163 link_names.size(), joint_origins.size());
169 for (
size_t i = 1; i < link_names.size(); ++i)
172 if (urdf_model_->getLink(link_names[i]))
178 auto link = std::make_shared<urdf::Link>();
179 link->name = link_names[i];
180 urdf_model_->links_.insert(std::make_pair(link_names[i], link));
181 auto joint = std::make_shared<urdf::Joint>();
182 joint->name = link_names[i - 1] +
"-" + link_names[i] +
"-joint";
184 joint->parent_to_joint_origin_transform.clear();
185 if (!joint_origins.empty())
187 geometry_msgs::Pose o = joint_origins[i - 1];
188 joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z);
189 joint->parent_to_joint_origin_transform.rotation =
190 urdf::Rotation(o.orientation.x, o.orientation.y, o.orientation.z, o.orientation.w);
193 joint->parent_link_name = link_names[i - 1];
194 joint->child_link_name = link_names[i];
195 if (type ==
"planar")
196 joint->type = urdf::Joint::PLANAR;
197 else if (type ==
"floating")
198 joint->type = urdf::Joint::FLOATING;
199 else if (type ==
"revolute")
200 joint->type = urdf::Joint::REVOLUTE;
201 else if (type ==
"continuous")
202 joint->type = urdf::Joint::CONTINUOUS;
203 else if (type ==
"prismatic")
204 joint->type = urdf::Joint::PRISMATIC;
205 else if (type ==
"fixed")
206 joint->type = urdf::Joint::FIXED;
214 joint->axis = joint_axis;
215 if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC)
217 auto limits = std::make_shared<urdf::JointLimits>();
218 limits->lower = -boost::math::constants::pi<double>();
219 limits->upper = boost::math::constants::pi<double>();
221 joint->limits = limits;
223 urdf_model_->joints_.insert(std::make_pair(joint->name, joint));
228 RobotModelBuilder& RobotModelBuilder::addInertial(
const std::string& link_name,
double mass, geometry_msgs::Pose origin,
229 double ixx,
double ixy,
double ixz,
double iyy,
double iyz,
232 if (!urdf_model_->getLink(link_name))
239 auto inertial = std::make_shared<urdf::Inertial>();
240 inertial->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
241 inertial->origin.rotation =
242 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
243 inertial->mass = mass;
251 urdf::LinkSharedPtr link;
252 urdf_model_->getLink(link_name, link);
253 link->inertial = inertial;
258 RobotModelBuilder& RobotModelBuilder::addVisualBox(
const std::string& link_name,
const std::vector<double>& size,
259 geometry_msgs::Pose origin)
261 auto vis = std::make_shared<urdf::Visual>();
262 auto geometry = std::make_shared<urdf::Box>();
263 geometry->dim = urdf::Vector3(size[0], size[1], size[2]);
264 vis->geometry = geometry;
265 addLinkVisual(link_name, vis, origin);
269 RobotModelBuilder& RobotModelBuilder::addCollisionSphere(
const std::string& link_name,
double radius,
270 geometry_msgs::Pose origin)
272 auto coll = std::make_shared<urdf::Collision>();
273 auto geometry = std::make_shared<urdf::Sphere>();
274 geometry->radius = radius;
275 coll->geometry = geometry;
276 addLinkCollision(link_name, coll, origin);
280 RobotModelBuilder& RobotModelBuilder::addCollisionBox(
const std::string& link_name,
const std::vector<double>& dims,
281 geometry_msgs::Pose origin)
283 if (dims.size() != 3)
285 ROS_ERROR(
"There can only be 3 dimensions of a box (given %zu!)", dims.size());
289 auto coll = std::make_shared<urdf::Collision>();
290 auto geometry = std::make_shared<urdf::Box>();
291 geometry->dim = urdf::Vector3(dims[0], dims[1], dims[2]);
292 coll->geometry = geometry;
293 addLinkCollision(link_name, coll, origin);
297 RobotModelBuilder& RobotModelBuilder::addCollisionMesh(
const std::string& link_name,
const std::string& filename,
298 geometry_msgs::Pose origin)
300 auto coll = std::make_shared<urdf::Collision>();
301 auto geometry = std::make_shared<urdf::Mesh>();
302 geometry->filename = filename;
303 coll->geometry = geometry;
304 addLinkCollision(link_name, coll, origin);
308 void RobotModelBuilder::addLinkCollision(
const std::string& link_name,
const urdf::CollisionSharedPtr& collision,
309 geometry_msgs::Pose origin)
311 if (!urdf_model_->getLink(link_name))
317 collision->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
318 collision->origin.rotation =
319 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
321 urdf::LinkSharedPtr link;
322 urdf_model_->getLink(link_name, link);
323 link->collision_array.push_back(collision);
326 void RobotModelBuilder::addLinkVisual(
const std::string& link_name,
const urdf::VisualSharedPtr& vis,
327 geometry_msgs::Pose origin)
329 if (!urdf_model_->getLink(link_name))
335 vis->origin.position = urdf::Vector3(origin.position.x, origin.position.y, origin.position.z);
336 vis->origin.rotation =
337 urdf::Rotation(origin.orientation.x, origin.orientation.y, origin.orientation.z, origin.orientation.w);
339 urdf::LinkSharedPtr link;
340 urdf_model_->getLink(link_name, link);
341 if (!link->visual_array.empty())
343 link->visual_array.push_back(vis);
345 else if (link->visual)
347 link->visual_array.push_back(link->visual);
348 link->visual.reset();
349 link->visual_array.push_back(vis);
357 RobotModelBuilder& RobotModelBuilder::addVirtualJoint(
const std::string& parent_frame,
const std::string& child_link,
358 const std::string& type,
const std::string& name)
362 new_virtual_joint.
name_ = parent_frame +
"-" + child_link +
"-virtual_joint";
365 new_virtual_joint.
type_ = type;
368 srdf_writer_->virtual_joints_.push_back(new_virtual_joint);
372 RobotModelBuilder& RobotModelBuilder::addGroupChain(
const std::string& base_link,
const std::string& tip_link,
373 const std::string& name)
377 new_group.
name_ = base_link +
"-" + tip_link +
"-chain-group";
380 new_group.
chains_.push_back(std::make_pair(base_link, tip_link));
381 srdf_writer_->groups_.push_back(new_group);
385 RobotModelBuilder& RobotModelBuilder::addGroup(
const std::vector<std::string>& links,
386 const std::vector<std::string>& joints,
const std::string& name)
392 srdf_writer_->groups_.push_back(new_group);
396 RobotModelBuilder& RobotModelBuilder::addEndEffector(
const std::string& name,
const std::string& parent_link,
397 const std::string& parent_group,
398 const std::string& component_group)
405 srdf_writer_->end_effectors_.push_back(eef);
409 void RobotModelBuilder::addJointProperty(
const std::string& joint_name,
const std::string& property_name,
410 const std::string& value)
412 srdf_writer_->joint_properties_[joint_name][property_name] = value;
415 bool RobotModelBuilder::isValid()
420 moveit::core::RobotModelPtr RobotModelBuilder::build()
423 std::map<std::string, std::string> parent_link_tree;
424 parent_link_tree.clear();
428 urdf_model_->initTree(parent_link_tree);
430 catch (urdf::ParseError& e)
439 urdf_model_->initRoot(parent_link_tree);
441 catch (urdf::ParseError& e)
446 srdf_writer_->updateSRDFModel(*urdf_model_);
447 robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_writer_->srdf_model_);