robot_model_loader.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, E. Gil Jones */
36 
39 #include <ros/ros.h>
40 
41 #include <memory>
42 #include <typeinfo>
43 
44 namespace robot_model_loader
45 {
46 RobotModelLoader::RobotModelLoader(const std::string& robot_description, bool load_kinematics_solvers)
47 {
48  Options opt(robot_description);
49  opt.load_kinematics_solvers_ = load_kinematics_solvers;
50  configure(opt);
51 }
52 
53 RobotModelLoader::RobotModelLoader(const Options& opt)
54 {
55  configure(opt);
56 }
57 
59 {
60  // Make sure we destroy the robot model first. It contains the loaded
61  // kinematics plugins, and those must be destroyed before the pluginlib class
62  // that implements them is destroyed (that happens when kinematics_loader_ is
63  // destroyed below). This is a workaround - ideally pluginlib would handle
64  // this better.
65  model_.reset();
66  rdf_loader_.reset();
67  kinematics_loader_.reset();
68 }
69 
70 namespace
71 {
72 bool canSpecifyPosition(const moveit::core::JointModel* jmodel, const unsigned int index)
73 {
74  bool ok = false;
75  if (jmodel->getType() == moveit::core::JointModel::PLANAR && index == 2)
76  ROS_ERROR("Cannot specify position limits for orientation of planar joint '%s'", jmodel->getName().c_str());
77  else if (jmodel->getType() == moveit::core::JointModel::FLOATING && index > 2)
78  ROS_ERROR("Cannot specify position limits for orientation of floating joint '%s'", jmodel->getName().c_str());
79  else if (jmodel->getType() == moveit::core::JointModel::REVOLUTE &&
80  static_cast<const moveit::core::RevoluteJointModel*>(jmodel)->isContinuous())
81  ROS_ERROR("Cannot specify position limits for continuous joint '%s'", jmodel->getName().c_str());
82  else
83  ok = true;
84  return ok;
85 }
86 } // namespace
87 
88 void RobotModelLoader::configure(const Options& opt)
89 {
91  moveit::tools::Profiler::ScopedBlock prof_block("RobotModelLoader::configure");
92 
94  if (!opt.urdf_string_.empty() && !opt.srdf_string_.empty())
95  rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(opt.urdf_string_, opt.srdf_string_);
96  else
97  rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(opt.robot_description_);
98  if (rdf_loader_->getURDF())
99  {
100  const srdf::ModelSharedPtr& srdf =
101  rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : std::make_shared<srdf::Model>();
102  model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader_->getURDF(), srdf);
103  }
104 
105  if (model_ && !rdf_loader_->getRobotDescription().empty())
106  {
107  moveit::tools::Profiler::ScopedBlock prof_block2("RobotModelLoader::configure joint limits");
108 
109  // if there are additional joint limits specified in some .yaml file, read those in
110  ros::NodeHandle nh("~");
111 
112  for (moveit::core::JointModel* joint_model : model_->getJointModels())
113  {
114  std::vector<moveit_msgs::JointLimits> joint_limit = joint_model->getVariableBoundsMsg();
115  for (std::size_t joint_id = 0; joint_id < joint_limit.size(); ++joint_id)
116  {
117  std::string prefix =
118  rdf_loader_->getRobotDescription() + "_planning/joint_limits/" + joint_limit[joint_id].joint_name + "/";
119 
120  double max_position;
121  if (nh.getParam(prefix + "max_position", max_position))
122  {
123  if (canSpecifyPosition(joint_model, joint_id))
124  {
125  joint_limit[joint_id].has_position_limits = true;
126  joint_limit[joint_id].max_position = max_position;
127  }
128  }
129  double min_position;
130  if (nh.getParam(prefix + "min_position", min_position))
131  {
132  if (canSpecifyPosition(joint_model, joint_id))
133  {
134  joint_limit[joint_id].has_position_limits = true;
135  joint_limit[joint_id].min_position = min_position;
136  }
137  }
138  double max_velocity;
139  if (nh.getParam(prefix + "max_velocity", max_velocity))
140  {
141  joint_limit[joint_id].has_velocity_limits = true;
142  joint_limit[joint_id].max_velocity = max_velocity;
143  }
144  bool has_vel_limits;
145  if (nh.getParam(prefix + "has_velocity_limits", has_vel_limits))
146  joint_limit[joint_id].has_velocity_limits = has_vel_limits;
147 
148  double max_acc;
149  if (nh.getParam(prefix + "max_acceleration", max_acc))
150  {
151  joint_limit[joint_id].has_acceleration_limits = true;
152  joint_limit[joint_id].max_acceleration = max_acc;
153  }
154  bool has_acc_limits;
155  if (nh.getParam(prefix + "has_acceleration_limits", has_acc_limits))
156  joint_limit[joint_id].has_acceleration_limits = has_acc_limits;
157  }
158  joint_model->setVariableBounds(joint_limit);
159  }
160  }
161 
162  if (model_ && opt.load_kinematics_solvers_)
164 
165  ROS_DEBUG_STREAM_NAMED("robot_model_loader",
166  "Loaded kinematic model in " << (ros::WallTime::now() - start).toSec() << " seconds");
167 }
168 
169 void RobotModelLoader::loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader)
170 {
172  moveit::tools::Profiler::ScopedBlock prof_block("RobotModelLoader::loadKinematicsSolvers");
173 
174  if (rdf_loader_ && model_)
175  {
176  // load the kinematics solvers
177  if (kloader)
178  kinematics_loader_ = kloader;
179  else
181  std::make_shared<kinematics_plugin_loader::KinematicsPluginLoader>(rdf_loader_->getRobotDescription());
182  moveit::core::SolverAllocatorFn kinematics_allocator =
183  kinematics_loader_->getLoaderFunction(rdf_loader_->getSRDF());
184  const std::vector<std::string>& groups = kinematics_loader_->getKnownGroups();
185  std::stringstream ss;
186  std::copy(groups.begin(), groups.end(), std::ostream_iterator<std::string>(ss, " "));
187  ROS_DEBUG_STREAM("Loaded information about the following groups: '" << ss.str() << "'");
188  if (groups.empty() && !model_->getJointModelGroups().empty())
189  ROS_WARN("No kinematics plugins defined. Fill and load kinematics.yaml!");
190 
191  std::map<std::string, moveit::core::SolverAllocatorFn> imap;
192  for (const std::string& group : groups)
193  {
194  // Check if a group in kinematics.yaml exists in the srdf
195  if (!model_->hasJointModelGroup(group))
196  continue;
197 
198  const moveit::core::JointModelGroup* jmg = model_->getJointModelGroup(group);
199 
200  kinematics::KinematicsBasePtr solver = kinematics_allocator(jmg);
201  if (solver)
202  {
203  std::string error_msg;
204  if (solver->supportsGroup(jmg, &error_msg))
205  {
206  imap[group] = kinematics_allocator;
207  }
208  else
209  {
210  const auto& s = *solver; // avoid clang-tidy's -Wpotentially-evaluated-expression
211  ROS_ERROR("Kinematics solver %s does not support joint group %s. Error: %s", typeid(s).name(), group.c_str(),
212  error_msg.c_str());
213  }
214  }
215  else
216  {
217  ROS_ERROR("Kinematics solver could not be instantiated for joint group %s.", group.c_str());
218  }
219  }
220  model_->setKinematicsAllocators(imap);
221 
222  // set the default IK timeouts
223  const std::map<std::string, double>& timeout = kinematics_loader_->getIKTimeout();
224  for (const std::pair<const std::string, double>& it : timeout)
225  {
226  if (!model_->hasJointModelGroup(it.first))
227  continue;
228  moveit::core::JointModelGroup* jmg = model_->getJointModelGroup(it.first);
229  jmg->setDefaultIKTimeout(it.second);
230  }
231  }
232 }
233 } // namespace robot_model_loader
robot_model_loader::RobotModelLoader::model_
moveit::core::RobotModelPtr model_
Definition: robot_model_loader.h:162
moveit::core::JointModel::PLANAR
PLANAR
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
s
XmlRpcServer s
ros.h
robot_model_loader
Definition: robot_model_loader.h:44
robot_model_loader::RobotModelLoader::rdf_loader_
rdf_loader::RDFLoaderPtr rdf_loader_
Definition: robot_model_loader.h:163
moveit::core::JointModel::getName
const std::string & getName() const
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
moveit::tools::Profiler::ScopedStart
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
moveit::core::RevoluteJointModel::isContinuous
bool isContinuous() const
ok
ROSCPP_DECL bool ok()
moveit::core::JointModel::getType
JointType getType() const
moveit::core::JointModel::REVOLUTE
REVOLUTE
robot_model_loader::RobotModelLoader::configure
void configure(const Options &opt)
Definition: robot_model_loader.cpp:120
name
std::string name
moveit::core::SolverAllocatorFn
boost::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
ros::WallTime::now
static WallTime now()
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
robot_model_loader::RobotModelLoader::RobotModelLoader
RobotModelLoader(const Options &opt=Options())
Default constructor.
Definition: robot_model_loader.cpp:85
ros::WallTime
robot_model_loader::RobotModelLoader::~RobotModelLoader
~RobotModelLoader()
Definition: robot_model_loader.cpp:90
start
ROSCPP_DECL void start()
srdf
moveit::tools::Profiler::ScopedBlock
moveit::core::JointModelGroup
moveit::core::JointModelGroup::setDefaultIKTimeout
void setDefaultIKTimeout(double ik_timeout)
moveit::core::RevoluteJointModel
robot_model_loader::RobotModelLoader::loadKinematicsSolvers
void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader=kinematics_plugin_loader::KinematicsPluginLoaderPtr())
Load the kinematics solvers into the kinematic model. This is done by default, unless disabled explic...
Definition: robot_model_loader.cpp:201
moveit::core::JointModel::FLOATING
FLOATING
profiler.h
robot_model_loader::RobotModelLoader::kinematics_loader_
kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
Definition: robot_model_loader.h:164
moveit::core::JointModel
ros::NodeHandle
robot_model_loader.h


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:20