-
Notifications
You must be signed in to change notification settings - Fork 65
/
Copy pathconstrained_ik.cpp
487 lines (421 loc) · 16.1 KB
/
constrained_ik.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
/**
* @file constrained_ik.cpp
* @brief Constrained Inverse Kinematic Solver
*
* @author dsolomon
* @date Sep 15, 2013
* @version TODO
* @bug No known bugs
*
* @copyright Copyright (c) 2013, Southwest Research Institute
*
* @par License
* Software License Agreement (Apache License)
* @par
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
* http://www.apache.org/licenses/LICENSE-2.0
* @par
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <constrained_ik/constrained_ik.h>
#include "constrained_ik/constraint_group.h"
#include <boost/make_shared.hpp>
#include <constrained_ik/constraint_results.h>
#include <ros/ros.h>
const std::vector<std::string> SUPPORTED_COLLISION_DETECTORS = {"IndustrialFCL", "CollisionDetectionOpenVDB"}; /**< Supported collision detector */
namespace constrained_ik
{
using Eigen::MatrixXd;
using Eigen::VectorXd;
using Eigen::Affine3d;
Constrained_IK::Constrained_IK(const ros::NodeHandle &nh) : nh_(nh)
{
initialized_ = false;
loadDefaultSolverConfiguration();
}
void Constrained_IK::addConstraintsFromParamServer(const std::string ¶meter_name)
{
std::vector<std::pair<bool, Constraint*> > constraints = loadConstraintsFromParamServer(parameter_name);
for (std::size_t i = 0; i < constraints.size(); ++i)
{
const bool is_primary = constraints[i].first;
Constraint* constraint = constraints[i].second;
if (is_primary)
addConstraint(constraint, constraint_types::Primary);
else
addConstraint(constraint, constraint_types::Auxiliary);
}
}
std::vector<std::pair<bool, Constraint*> > Constrained_IK::loadConstraintsFromParamServer(const std::string& parameter_name)
{
XmlRpc::XmlRpcValue constraints_xml;
boost::shared_ptr<pluginlib::ClassLoader<constrained_ik::Constraint> > constraint_loader;
constraint_loader.reset(new pluginlib::ClassLoader<constrained_ik::Constraint>("constrained_ik", "constrained_ik::Constraint"));
std::vector<std::pair<bool, Constraint*> > constraints;
if (!nh_.getParam(parameter_name, constraints_xml))
{
ROS_WARN("Unable to find ros parameter: %s", parameter_name.c_str());
return constraints;
}
if(constraints_xml.getType() != XmlRpc::XmlRpcValue::TypeArray)
{
ROS_ERROR("ROS parameter %s must be an array", parameter_name.c_str());
return constraints;
}
for (int i = 0; i < constraints_xml.size(); ++i)
{
XmlRpc::XmlRpcValue constraint_xml = constraints_xml[i];
if (constraint_xml.hasMember("class") &&
constraint_xml["class"].getType() == XmlRpc::XmlRpcValue::TypeString &&
constraint_xml.hasMember("primary") &&
constraint_xml["primary"].getType() == XmlRpc::XmlRpcValue::TypeBoolean)
{
std::string class_name = constraint_xml["class"];
bool is_primary = constraint_xml["primary"];
Constraint *constraint;
try
{
constraint = constraint_loader->createUnmanagedInstance(class_name);
constraint->loadParameters(constraint_xml);
constraints.push_back(std::make_pair(is_primary, constraint));
}
catch (pluginlib::PluginlibException& ex)
{
ROS_ERROR("Couldn't load constraint named %s.\n Error: %s", class_name.c_str(), ex.what());
}
}
else
{
ROS_ERROR("Constraint must have class(string) and primary(boolean) members");
}
}
return constraints;
}
void Constrained_IK::loadDefaultSolverConfiguration()
{
ConstrainedIKConfiguration config;
config.debug_mode = false;
config.allow_joint_convergence = false;
config.allow_primary_normalization = true;
config.allow_auxiliary_nomalization = true;
config.limit_primary_motion = false;
config.limit_auxiliary_motion = false;
config.limit_auxiliary_interations = false;
config.solver_max_iterations = 500;
config.solver_min_iterations = 0;
config.auxiliary_max_iterations = 5;
config.primary_max_motion = 2.0;
config.auxiliary_max_motion = 0.2;
config.primary_norm = 1.0;
config.auxiliary_norm = 0.2;
config.primary_gain = 1.0;
config.auxiliary_gain = 1.0;
config.joint_convergence_tol = 0.0001;
setSolverConfiguration(config);
}
void Constrained_IK::setSolverConfiguration(const ConstrainedIKConfiguration &config)
{
config_ = config;
validateConstrainedIKConfiguration<ConstrainedIKConfiguration>(config_);
}
constrained_ik::ConstraintResults Constrained_IK::evalConstraint(constraint_types::ConstraintTypes constraint_type, const constrained_ik::SolverState &state) const
{
switch(constraint_type)
{
case constraint_types::Primary:
return primary_constraints_.evalConstraint(state);
case constraint_types::Auxiliary:
return auxiliary_constraints_.evalConstraint(state);
}
}
Eigen::MatrixXd Constrained_IK::calcNullspaceProjection(const Eigen::MatrixXd &J) const
{
MatrixXd J_pinv = calcDampedPseudoinverse(J);
MatrixXd JplusJ = J_pinv * J;
int mn = JplusJ.rows();
MatrixXd P = MatrixXd::Identity(mn,mn)-JplusJ;
return (P);
}
Eigen::MatrixXd Constrained_IK::calcNullspaceProjectionTheRightWay(const Eigen::MatrixXd &A) const
{
Eigen::JacobiSVD<MatrixXd> svd(A, Eigen::ComputeFullV);
MatrixXd V(svd.matrixV());
// determine rank using same algorithym as latest Eigen
// TODO replace next 10 lines of code with rnk = svd.rank(); once eigen3 is updated
int rnk = 0;
if(svd.singularValues().size()==0)
{
rnk = 0;
}
else
{
double threshold = std::min(A.rows(),A.cols())*Eigen::NumTraits<double>::epsilon();
double premultiplied_threshold = svd.singularValues().coeff(0) * threshold;
rnk = svd.nonzeroSingularValues()-1;
while(rnk>=0 && svd.singularValues().coeff(rnk) < premultiplied_threshold) --rnk;
rnk++;
}
// zero singular vectors in the range of A
for(int i=0; i<rnk; ++i)
{
for(int j=0; j<A.cols(); j++) V(j,i) = 0;
}
MatrixXd P = V * V.transpose();
return(P);
}
Eigen::MatrixXd Constrained_IK::calcDampedPseudoinverse(const Eigen::MatrixXd &J) const
{
MatrixXd J_pinv;
if (basic_kin::BasicKin::dampedPInv(J,J_pinv))
{
return J_pinv;
}
else
{
ROS_ERROR_STREAM("Not able to calculate damped pseudoinverse!");
throw std::runtime_error("Not able to calculate damped pseudoinverse! IK solution may be invalid.");
}
}
bool Constrained_IK::calcInvKin(const Eigen::Affine3d &goal,
const Eigen::VectorXd &joint_seed,
Eigen::VectorXd &joint_angles) const
{
return calcInvKin(goal,joint_seed, planning_scene::PlanningSceneConstPtr(), joint_angles);
}
bool Constrained_IK::calcInvKin(const Eigen::Affine3d &goal,
const Eigen::VectorXd &joint_seed,
const planning_scene::PlanningSceneConstPtr planning_scene,
Eigen::VectorXd &joint_angles) const
{
double dJoint_norm;
SolverStatus status;
// initialize state
joint_angles = joint_seed; // initialize result to seed value
constrained_ik::SolverState state = getState(goal, joint_seed); // create state vars for this IK solve
state.condition = checkInitialized();
state.planning_scene = planning_scene;
state.group_name = kin_.getJointModelGroup()->getName();
//TODO: Does this still belong here?
if(planning_scene)
{
state.robot_state = robot_state::RobotStatePtr(new moveit::core::RobotState(planning_scene->getCurrentState()));
//Check and make sure the correct collision detector is loaded.
auto pos = std::find(SUPPORTED_COLLISION_DETECTORS.begin(),SUPPORTED_COLLISION_DETECTORS.end(),
planning_scene->getActiveCollisionDetectorName());
if (pos == SUPPORTED_COLLISION_DETECTORS.end())
{
std::stringstream error_message;
error_message<<" Constrained IK requires the use of collision detectors: ";
for(auto& d : SUPPORTED_COLLISION_DETECTORS)
{
error_message<<"'"<< d<<"' ";
}
error_message<<".\nSet or add the 'collision_detector' parameter to an allowed collision detector in the move_group.launch file"<<std::endl;
throw std::runtime_error(error_message.str());
}
state.collision_robot = boost::dynamic_pointer_cast<const collision_detection::CollisionRobotIndustrial>(planning_scene->getCollisionRobot());
state.collision_world = boost::dynamic_pointer_cast<const collision_detection::CollisionWorldIndustrial>(planning_scene->getCollisionWorld());
}
if (state.condition == initialization_state::NothingInitialized || state.condition == initialization_state::AuxiliaryOnly)
throw std::runtime_error("Must call init() before using Constrained_IK and have a primary constraint.");
//Cache the joint angles to return if max iteration is reached.
Eigen::VectorXd cached_joint_angles = joint_seed;
// iterate until solution converges (or aborted)
while (true)
{
// re-update internal state variables
updateState(state, joint_angles);
// calculate a Jacobian (relating joint-space updates/deltas to cartesian-space errors/deltas)
// and the associated cartesian-space error/delta vector
// Primary Constraints
constrained_ik::ConstraintResults primary = evalConstraint(constraint_types::Primary, state);
// TODO since we already have J_p = USV, use that to get null-projection too.
// otherwise, we are repeating the expensive calculation of the SVD
VectorXd dJoint_p;
dJoint_p.setZero(joint_seed.size());
if (!primary.isEmpty()) // This is required because not all constraints always return data.
{
MatrixXd Ji_p = calcDampedPseudoinverse(primary.jacobian);
dJoint_p = config_.primary_gain*(Ji_p*primary.error);
dJoint_norm = dJoint_p.norm();
if(config_.allow_primary_normalization && dJoint_norm > config_.primary_norm)// limit maximum update radian/meter
{
dJoint_p = config_.primary_norm * (dJoint_p/dJoint_norm);
dJoint_norm = dJoint_p.norm();
}
state.primary_sum += dJoint_norm;
}
// Auxiliary Constraints
VectorXd dJoint_a;
constrained_ik::ConstraintResults auxiliary;
dJoint_a.setZero(dJoint_p.size());
if (state.condition == initialization_state::PrimaryAndAuxiliary)
{
if (!((config_.limit_auxiliary_motion && state.auxiliary_sum >= config_.auxiliary_max_motion) ||
(config_.limit_auxiliary_interations && state.iter > config_.auxiliary_max_iterations)))
{
auxiliary = evalConstraint(constraint_types::Auxiliary, state);
if (!auxiliary.isEmpty()) // This is required because not all constraints always return data.
{
MatrixXd N_p = calcNullspaceProjectionTheRightWay(primary.jacobian);
MatrixXd Jnull_a = calcDampedPseudoinverse(auxiliary.jacobian*N_p);
dJoint_a = config_.auxiliary_gain*Jnull_a*(auxiliary.error-auxiliary.jacobian*dJoint_p);
dJoint_norm = dJoint_a.norm();
if(config_.allow_auxiliary_nomalization && dJoint_norm > config_.auxiliary_norm)// limit maximum update radian/meter
{
dJoint_a = config_.auxiliary_norm * (dJoint_a/dJoint_norm);
dJoint_norm = dJoint_a.norm();
}
state.auxiliary_sum += dJoint_norm;
}
}
else
{
state.auxiliary_at_limit = true;
}
}
status = checkStatus(state, primary, auxiliary);
if (status == Converged)
{
ROS_DEBUG_STREAM("Found IK solution in " << state.iter << " iterations: " << joint_angles.transpose());
return true;
}
else if (status == NotConverged)
{
// update joint solution by the calculated update (or a partial fraction)
joint_angles += (dJoint_p + dJoint_a);
clipToJointLimits(joint_angles);
}
else if (status == Failed)
{
joint_angles = cached_joint_angles;
return false;
}
}
}
SolverStatus Constrained_IK::checkStatus(const constrained_ik::SolverState &state, const constrained_ik::ConstraintResults &primary, const constrained_ik::ConstraintResults &auxiliary) const
{
// Check the status of convergence
if(state.condition == initialization_state::PrimaryAndAuxiliary)
{
bool status = (primary.status && auxiliary.status);
if (state.iter > config_.solver_min_iterations)
{
if (!status && primary.status && state.auxiliary_at_limit)
{
ROS_DEBUG("Auxiliary motion or iteration limit reached!");
return Converged;
}
else if(status)
{
return Converged;
}
}
}
if(state.condition == initialization_state::PrimaryOnly)
{
if (primary.status && state.iter > config_.solver_min_iterations)
{
return Converged;
}
}
// check for joint convergence
// - this is an error: joints stabilize, but goal pose not reached
if (config_.allow_joint_convergence)
{
if (state.joints_delta.cwiseAbs().maxCoeff() < config_.joint_convergence_tol)
{
if (state.iter > config_.solver_min_iterations)
{
ROS_DEBUG_STREAM("Joint convergence reached " << state.iter << " / " << config_.solver_max_iterations << " iterations before convergence.");
return Converged;
}
}
}
if (state.iter > config_.solver_max_iterations || (config_.limit_primary_motion && state.primary_sum >= config_.primary_max_motion))
{
if (!primary.status)
{
if (config_.limit_primary_motion && state.primary_sum >= config_.primary_max_motion)
{
ROS_WARN_STREAM("Primary reached max allowed motion, no solution returned.");
}
else
{
ROS_WARN_STREAM("Solver reached max allowed iteration, no solution returned.");
}
return Failed;
}
else if (state.condition == initialization_state::PrimaryAndAuxiliary)
{
ROS_WARN_STREAM("Maximum iterations reached but primary converged so returning solution.");
return Converged;
}
}
return NotConverged;
}
void Constrained_IK::clearConstraintList()
{
primary_constraints_.clear();
auxiliary_constraints_.clear();
}
void Constrained_IK::clipToJointLimits(Eigen::VectorXd &joints) const
{
const MatrixXd limits = kin_.getLimits();
const VectorXd orig_joints(joints);
if (joints.size() != limits.rows())
throw std::invalid_argument("clipToJointLimits: Unexpected number of joints");
for (size_t i=0; i<limits.rows(); ++i)
{
joints[i] = std::max(limits(i,0), std::min(limits(i,1), joints[i]));
}
if (config_.debug_mode && !joints.isApprox(orig_joints))
ROS_WARN("Joints have been clipped");
}
void Constrained_IK::init(const basic_kin::BasicKin &kin)
{
if (!kin.checkInitialized())
throw std::invalid_argument("Input argument 'BasicKin' must be initialized");
kin_ = kin;
initialized_ = true;
primary_constraints_.init(this);
auxiliary_constraints_.init(this);
}
double Constrained_IK::rangedAngle(double angle)
{
angle = copysign(fmod(fabs(angle),2.0*M_PI), angle);
if (angle < -M_PI) return angle+2.*M_PI;
if (angle > M_PI) return angle-2.*M_PI;
return angle;
}
constrained_ik::SolverState Constrained_IK::getState(const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed) const
{
if (!kin_.checkJoints(joint_seed))
throw std::invalid_argument("Seed doesn't match kinematic model");
if (!goal.matrix().block(0,0,3,3).isUnitary(1e-6))
throw std::invalid_argument("Goal pose not proper affine");
return constrained_ik::SolverState(goal, joint_seed);
}
void Constrained_IK::updateState(constrained_ik::SolverState &state, const Eigen::VectorXd &joints) const
{
// update maximum iterations
state.iter++;
// update joint convergence
state.joints_delta = joints - state.joints;
state.joints = joints;
kin_.calcFwdKin(joints, state.pose_estimate);
if(state.planning_scene && state.robot_state)
{
state.robot_state->setJointGroupPositions(kin_.getJointModelGroup()->getName(), joints);
state.robot_state->update();
}
if (config_.debug_mode)
state.iteration_path.push_back(joints);
}
} // namespace constrained_ik