48 Options opt(robot_description);
49 opt.load_kinematics_solvers_ = load_kinematics_solvers;
76 ROS_ERROR(
"Cannot specify position limits for orientation of planar joint '%s'", jmodel->
getName().c_str());
78 ROS_ERROR(
"Cannot specify position limits for orientation of floating joint '%s'", jmodel->
getName().c_str());
81 ROS_ERROR(
"Cannot specify position limits for continuous joint '%s'", jmodel->
getName().c_str());
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_);
97 rdf_loader_ = std::make_shared<rdf_loader::RDFLoader>(opt.robot_description_);
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)
118 rdf_loader_->getRobotDescription() +
"_planning/joint_limits/" + joint_limit[joint_id].joint_name +
"/";
121 if (nh.getParam(prefix +
"max_position", max_position))
123 if (canSpecifyPosition(joint_model, joint_id))
125 joint_limit[joint_id].has_position_limits =
true;
126 joint_limit[joint_id].max_position = max_position;
130 if (nh.getParam(prefix +
"min_position", min_position))
132 if (canSpecifyPosition(joint_model, joint_id))
134 joint_limit[joint_id].has_position_limits =
true;
135 joint_limit[joint_id].min_position = min_position;
139 if (nh.getParam(prefix +
"max_velocity", max_velocity))
141 joint_limit[joint_id].has_velocity_limits =
true;
142 joint_limit[joint_id].max_velocity = max_velocity;
145 if (nh.getParam(prefix +
"has_velocity_limits", has_vel_limits))
146 joint_limit[joint_id].has_velocity_limits = has_vel_limits;
149 if (nh.getParam(prefix +
"max_acceleration", max_acc))
151 joint_limit[joint_id].has_acceleration_limits =
true;
152 joint_limit[joint_id].max_acceleration = max_acc;
155 if (nh.getParam(prefix +
"has_acceleration_limits", has_acc_limits))
156 joint_limit[joint_id].has_acceleration_limits = has_acc_limits;
158 joint_model->setVariableBounds(joint_limit);
162 if (
model_ && opt.load_kinematics_solvers_)
166 "Loaded kinematic model in " << (
ros::WallTime::now() - start).toSec() <<
" seconds");
181 std::make_shared<kinematics_plugin_loader::KinematicsPluginLoader>(
rdf_loader_->getRobotDescription());
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!");
191 std::map<std::string, moveit::core::SolverAllocatorFn> imap;
192 for (
const std::string& group : groups)
195 if (!
model_->hasJointModelGroup(group))
200 kinematics::KinematicsBasePtr solver = kinematics_allocator(jmg);
203 std::string error_msg;
204 if (solver->supportsGroup(jmg, &error_msg))
206 imap[group] = kinematics_allocator;
210 const auto&
s = *solver;
211 ROS_ERROR(
"Kinematics solver %s does not support joint group %s. Error: %s",
typeid(
s).
name(), group.c_str(),
217 ROS_ERROR(
"Kinematics solver could not be instantiated for joint group %s.", group.c_str());
220 model_->setKinematicsAllocators(imap);
224 for (
const std::pair<const std::string, double>& it : timeout)
226 if (!
model_->hasJointModelGroup(it.first))