moveit_opw_kinematics_plugin.cpp
Go to the documentation of this file.
3 
4 // abs
5 #include <cstdlib>
6 
7 // URDF, SRDF
8 #include <srdfdom/model.h>
9 #include <urdf_model/model.h>
10 
14 
15 // Eigen
16 #include <Eigen/Core>
17 #include <Eigen/Geometry>
19 
20 // OPW kinematics
21 #include "opw_kinematics/opw_io.h"
24 
25 // register OPWKinematics as a KinematicsBase implementation
27 
29 {
31 
32 MoveItOPWKinematicsPlugin::MoveItOPWKinematicsPlugin() : active_(false)
33 {
34 }
35 
36 bool MoveItOPWKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name,
37  const std::string& base_frame, const std::vector<std::string>& tip_frames,
38  double search_discretization)
39 {
40  bool debug = false;
41 
42  ROS_INFO_STREAM_NAMED("opw", "MoveItOPWKinematicsPlugin initializing");
43 
44  setValues(robot_description, group_name, base_frame, tip_frames, search_discretization);
45 
47  const srdf::ModelSharedPtr& srdf = rdf_loader.getSRDF();
48  const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader.getURDF();
49 
50  if (!urdf_model || !srdf)
51  {
52  ROS_ERROR_NAMED("opw", "URDF and SRDF must be loaded for OPW kinematics "
53  "solver to work.");
54  return false;
55  }
56 
57  robot_model_.reset(new robot_model::RobotModel(urdf_model, srdf));
58 
59  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
60  if (!joint_model_group_)
61  return false;
62 
63  if (debug)
64  {
65  std::cout << std::endl
66  << "Joint Model Variable Names: "
67  "------------------------------------------- "
68  << std::endl;
69  const std::vector<std::string> jm_names = joint_model_group_->getVariableNames();
70  std::copy(jm_names.begin(), jm_names.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
71  std::cout << std::endl;
72  }
73 
74  // Get the dimension of the planning group
75  dimension_ = joint_model_group_->getVariableCount();
76  ROS_INFO_STREAM_NAMED("opw", "Dimension planning group '"
77  << group_name << "': " << dimension_
78  << ". Active Joints Models: " << joint_model_group_->getActiveJointModels().size()
79  << ". Mimic Joint Models: " << joint_model_group_->getMimicJointModels().size());
80 
81  // Copy joint names
82  for (std::size_t i = 0; i < joint_model_group_->getActiveJointModels().size(); ++i)
83  {
84  ik_group_info_.joint_names.push_back(joint_model_group_->getActiveJointModelNames()[i]);
85  }
86 
87  if (debug)
88  {
89  ROS_ERROR_STREAM_NAMED("opw", "tip links available:");
90  std::copy(tip_frames_.begin(), tip_frames_.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
91  }
92 
93  // Make sure all the tip links are in the link_names vector
94  for (std::size_t i = 0; i < tip_frames_.size(); ++i)
95  {
96  if (!joint_model_group_->hasLinkModel(tip_frames_[i]))
97  {
98  ROS_ERROR_NAMED("opw", "Could not find tip name '%s' in joint group '%s'", tip_frames_[i].c_str(),
99  group_name.c_str());
100  return false;
101  }
102  ik_group_info_.link_names.push_back(tip_frames_[i]);
103  }
104 
105  // Choose what ROS service to send IK requests to
106  ROS_DEBUG_STREAM_NAMED("opw", "Looking for ROS service name on rosparam server with param: "
107  << "/kinematics_solver_service_name");
108  std::string ik_service_name;
109  lookupParam("kinematics_solver_service_name", ik_service_name, std::string("solve_ik"));
110 
111  // Setup the joint state groups that we need
112  robot_state_.reset(new robot_state::RobotState(robot_model_));
113  robot_state_->setToDefaultValues();
114 
115  // set geometric parameters for opw model
116  if (!setOPWParameters())
117  {
118  ROS_ERROR_STREAM_NAMED("opw", "Could not load opw parameters. Check kinematics.yaml.");
119  return false;
120  }
121 
122  // check geometric parameters for opw model
123  if (!selfTest())
124  {
125  ROS_ERROR_STREAM_NAMED("opw", "The opw parameters loaded from kinematics.yaml appear to be incorrect.");
126  return false;
127  }
128 
129  active_ = true;
130  ROS_DEBUG_NAMED("opw", "ROS service-based kinematics solver initialized");
131  return true;
132 }
133 
134 bool MoveItOPWKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joints)
135 {
137  {
138  ROS_ERROR_NAMED("opw", "This group cannot have redundant joints");
139  return false;
140  }
141  if (redundant_joints.size() > static_cast<std::size_t>(num_possible_redundant_joints_))
142  {
143  ROS_ERROR_NAMED("opw", "This group can only have %d redundant joints", num_possible_redundant_joints_);
144  return false;
145  }
146 
147  redundant_joint_indices_ = redundant_joints;
148 
149  return true;
150 }
151 
152 bool MoveItOPWKinematicsPlugin::isRedundantJoint(unsigned int index) const
153 {
154  for (std::size_t j = 0; j < redundant_joint_indices_.size(); ++j)
155  if (redundant_joint_indices_[j] == index)
156  return true;
157  return false;
158 }
159 
160 int MoveItOPWKinematicsPlugin::getJointIndex(const std::string& name) const
161 {
162  for (unsigned int i = 0; i < ik_group_info_.joint_names.size(); i++)
163  {
164  if (ik_group_info_.joint_names[i] == name)
165  return i;
166  }
167  return -1;
168 }
169 
170 bool MoveItOPWKinematicsPlugin::timedOut(const ros::WallTime& start_time, double duration) const
171 {
172  return ((ros::WallTime::now() - start_time).toSec() >= duration);
173 }
174 
176 {
177  const std::vector<double> joint_angles = { 0.1, -0.1, 0.2, -0.3, 0.5, -0.8 };
178 
179  auto fk_pose_opw = opw_kinematics::forward(opw_parameters_, &joint_angles[0]);
180  robot_state_->setJointGroupPositions(joint_model_group_, joint_angles);
181  auto fk_pose_moveit = robot_state_->getGlobalLinkTransform(tip_frames_[0]);
182  // group/robot might not be at origin, subtract base transform
183  auto base = robot_state_->getGlobalLinkTransform(base_frame_);
184  fk_pose_moveit = base.inverse() * fk_pose_moveit;
185 
186  if (!comparePoses(fk_pose_opw, fk_pose_moveit))
187  {
188  return false;
189  }
190 
191  // reset robot state
192  robot_state_->setToDefaultValues();
193  return true;
194 }
195 
196 bool MoveItOPWKinematicsPlugin::comparePoses(Eigen::Isometry3d& Ta, Eigen::Affine3d& Tb)
197 {
198  const float TOLERANCE = 1e-6;
199 
200  auto Ra = Ta.rotation();
201  auto Rb = Tb.rotation();
202  for (int i = 0; i < Ra.rows(); ++i)
203  {
204  for (int j = 0; j < Ra.cols(); ++j)
205  {
206  if (std::abs(Ra(i, j) - Rb(i, j)) > TOLERANCE)
207  {
208  ROS_ERROR_NAMED("opw", "Pose orientation error on element (%d, %d).", i, j);
209  ROS_ERROR_NAMED("opw", "opw: %f, moveit: %f.", Ra(i, j), Rb(i, j));
210  return false;
211  }
212  }
213  }
214 
215  auto pa = Ta.translation();
216  auto pb = Tb.translation();
217  for (int i = 0; i < 3; ++i)
218  {
219  if (std::abs(pa(i) - pb(i)) > TOLERANCE)
220  {
221  ROS_ERROR_NAMED("opw", "Pose position error on element (%d).", i);
222  ROS_ERROR_NAMED("opw", "opw: %f, moveit: %f.", pa(i), pb(i));
223  return false;
224  }
225  }
226  return true;
227 }
228 
229 bool MoveItOPWKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose,
230  const std::vector<double>& ik_seed_state, std::vector<double>& solution,
231  moveit_msgs::MoveItErrorCodes& error_code,
232  const kinematics::KinematicsQueryOptions& options) const
233 {
234  const IKCallbackFn solution_callback = 0;
235  std::vector<double> consistency_limits;
236 
237  return searchPositionIK(ik_pose, ik_seed_state, default_timeout_, solution, solution_callback, error_code,
238  consistency_limits, options);
239 }
240 
241 bool MoveItOPWKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
242  const std::vector<double>& ik_seed_state, double timeout,
243  std::vector<double>& solution,
244  moveit_msgs::MoveItErrorCodes& error_code,
245  const kinematics::KinematicsQueryOptions& options) const
246 {
247  const IKCallbackFn solution_callback = 0;
248  std::vector<double> consistency_limits;
249 
250  return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
251  options);
252 }
253 
254 bool MoveItOPWKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
255  const std::vector<double>& ik_seed_state, double timeout,
256  const std::vector<double>& consistency_limits,
257  std::vector<double>& solution,
258  moveit_msgs::MoveItErrorCodes& error_code,
259  const kinematics::KinematicsQueryOptions& options) const
260 {
261  const IKCallbackFn solution_callback = 0;
262  return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
263  options);
264 }
265 
266 bool MoveItOPWKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
267  const std::vector<double>& ik_seed_state, double timeout,
268  std::vector<double>& solution, const IKCallbackFn& solution_callback,
269  moveit_msgs::MoveItErrorCodes& error_code,
270  const kinematics::KinematicsQueryOptions& options) const
271 {
272  std::vector<double> consistency_limits;
273  return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
274  options);
275 }
276 
277 bool MoveItOPWKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
278  const std::vector<double>& ik_seed_state, double timeout,
279  const std::vector<double>& consistency_limits,
280  std::vector<double>& solution, const IKCallbackFn& solution_callback,
281  moveit_msgs::MoveItErrorCodes& error_code,
282  const kinematics::KinematicsQueryOptions& options) const
283 {
284  return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
285  options);
286 }
287 
288 bool MoveItOPWKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose,
289  const std::vector<double>& ik_seed_state, double timeout,
290  std::vector<double>& solution, const IKCallbackFn& solution_callback,
291  moveit_msgs::MoveItErrorCodes& error_code,
292  const std::vector<double>& consistency_limits,
293  const kinematics::KinematicsQueryOptions& options) const
294 {
295  // Convert single pose into a vector of one pose
296  std::vector<geometry_msgs::Pose> ik_poses;
297  ik_poses.push_back(ik_pose);
298 
299  return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
300  options);
301 }
302 
303 bool MoveItOPWKinematicsPlugin::searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
304  const std::vector<double>& ik_seed_state, double /*timeout*/,
305  const std::vector<double>& /*consistency_limits*/,
306  std::vector<double>& solution, const IKCallbackFn& solution_callback,
307  moveit_msgs::MoveItErrorCodes& error_code,
308  const kinematics::KinematicsQueryOptions& /*options*/) const
309 {
310  // Check if active
311  if (!active_)
312  {
313  ROS_ERROR_NAMED("opw", "kinematics not active");
314  error_code.val = error_code.NO_IK_SOLUTION;
315  return false;
316  }
317 
318  // Check if seed state correct
319  if (ik_seed_state.size() != dimension_)
320  {
322  "Seed state must have size " << dimension_ << " instead of size " << ik_seed_state.size());
323  error_code.val = error_code.NO_IK_SOLUTION;
324  return false;
325  }
326 
327  // Check that we have the same number of poses as tips
328  if (tip_frames_.size() != ik_poses.size())
329  {
330  ROS_ERROR_STREAM_NAMED("opw", "Mismatched number of pose requests (" << ik_poses.size() << ") to tip frames ("
331  << tip_frames_.size()
332  << ") in searchPositionIK");
333  error_code.val = error_code.NO_IK_SOLUTION;
334  return false;
335  }
336 
337  Eigen::Affine3d pose;
338  tf::poseMsgToEigen(ik_poses[0], pose);
339  std::vector<std::vector<double>> solutions;
340  if (!getAllIK(pose, solutions))
341  {
342  ROS_DEBUG_STREAM_NAMED("opw", "Failed to find IK solution");
343  error_code.val = error_code.NO_IK_SOLUTION;
344  return false;
345  }
346 
347  std::vector<LimitObeyingSol> limit_obeying_solutions;
348 
349  for (auto& sol : solutions)
350  {
351  robot_state_->setJointGroupPositions(joint_model_group_, sol);
352  // robot_state_->update(); // not required for checking bounds
353  if (!robot_state_->satisfiesBounds(joint_model_group_))
354  {
355  ROS_DEBUG_STREAM_NAMED("opw", "Solution is outside bounds");
356  continue;
357  }
358  limit_obeying_solutions.push_back({ sol, distance(sol, ik_seed_state) });
359  }
360 
361  if (limit_obeying_solutions.empty())
362  {
363  ROS_DEBUG_NAMED("opw", "None of the solutions is within joint limits");
364  return false;
365  }
366 
367  ROS_DEBUG_STREAM_NAMED("opw", "Solutions within limits: " << limit_obeying_solutions.size());
368 
369  // sort solutions by distance to seed state
370  std::sort(limit_obeying_solutions.begin(), limit_obeying_solutions.end());
371 
372  if (!solution_callback)
373  {
374  solution = limit_obeying_solutions.front().value;
375  return true;
376  }
377 
378  for (auto& sol : limit_obeying_solutions)
379  {
380  solution_callback(ik_poses[0], sol.value, error_code);
381  if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
382  {
383  solution = sol.value;
384  ROS_DEBUG_STREAM_NAMED("opw", "Solution passes callback");
385  return true;
386  }
387  }
388 
389  ROS_DEBUG_STREAM_NAMED("opw", "No solution fullfilled requirements of solution callback");
390  return false;
391 }
392 
393 bool MoveItOPWKinematicsPlugin::getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses,
394  const std::vector<double>& /*ik_seed_state*/,
395  std::vector<std::vector<double>>& solutions, KinematicsResult& /*result*/,
396  const kinematics::KinematicsQueryOptions& /*options*/) const
397 {
398  if (ik_poses.size() > 1 || ik_poses.size() == 0)
399  {
400  ROS_ERROR_STREAM_NAMED("opw", "You can only get all solutions for a single pose.");
401  return false;
402  }
403  Eigen::Affine3d pose;
404  tf::poseMsgToEigen(ik_poses[0], pose);
405  return getAllIK(pose, solutions);
406 }
407 
408 bool MoveItOPWKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
409  const std::vector<double>& joint_angles,
410  std::vector<geometry_msgs::Pose>& poses) const
411 {
412  if (!active_)
413  {
414  ROS_ERROR_NAMED("opw", "kinematics not active");
415  return false;
416  }
417  poses.resize(link_names.size());
418  if (joint_angles.size() != dimension_)
419  {
420  ROS_ERROR_NAMED("opw", "Joint angles vector must have size: %d", dimension_);
421  return false;
422  }
423 
424  // Check that we have the same number of poses as tips
425  if (tip_frames_.size() != poses.size())
426  {
427  ROS_ERROR_STREAM_NAMED("opw", "Mismatched number of pose requests (" << poses.size() << ") to tip frames ("
428  << tip_frames_.size()
429  << ") in searchPositionFK");
430  return false;
431  }
432 
433  // forward function expect pointer to first element of array of joint values
434  // that is why &joint_angles[0] is passed
435  tf::poseEigenToMsg(opw_kinematics::forward(opw_parameters_, &joint_angles[0]), poses[0]);
436 
437  return true;
438 }
439 
440 const std::vector<std::string>& MoveItOPWKinematicsPlugin::getJointNames() const
441 {
442  return ik_group_info_.joint_names;
443 }
444 
445 const std::vector<std::string>& MoveItOPWKinematicsPlugin::getLinkNames() const
446 {
447  return ik_group_info_.link_names;
448 }
449 
450 const std::vector<std::string>& MoveItOPWKinematicsPlugin::getVariableNames() const
451 {
452  return joint_model_group_->getVariableNames();
453 }
454 
456 {
457  ROS_INFO_STREAM("Getting kinematic parameters from parameter server.");
458 
459  ros::NodeHandle nh;
460 
461  std::map<std::string, double> geometric_parameters;
462  if (!lookupParam("opw_kinematics_geometric_parameters", geometric_parameters, {}))
463  {
464  ROS_ERROR_STREAM("Failed to load geometric parameters for ik solver.");
465  return false;
466  }
467 
468  std::vector<double> joint_offsets;
469  if (!lookupParam("opw_kinematics_joint_offsets", joint_offsets, {}))
470  {
471  ROS_ERROR_STREAM("Failed to load joint offsets for ik solver.");
472  return false;
473  }
474 
475  std::vector<int> joint_sign_corrections;
476  if (!lookupParam("opw_kinematics_joint_sign_corrections", joint_sign_corrections, {}))
477  {
478  ROS_ERROR_STREAM("Failed to load joint sign corrections for ik solver.");
479  return false;
480  }
481 
482  opw_parameters_.a1 = geometric_parameters["a1"];
483  opw_parameters_.a2 = geometric_parameters["a2"];
484  opw_parameters_.b = geometric_parameters["b"];
485  opw_parameters_.c1 = geometric_parameters["c1"];
486  opw_parameters_.c2 = geometric_parameters["c2"];
487  opw_parameters_.c3 = geometric_parameters["c3"];
488  opw_parameters_.c4 = geometric_parameters["c4"];
489 
490  if (joint_offsets.size() != 6)
491  {
492  ROS_ERROR_STREAM("Expected joint_offsets to contain 6 elements, but it has " << joint_offsets.size() << ".");
493  return false;
494  }
495 
496  if (joint_sign_corrections.size() != 6)
497  {
498  ROS_ERROR_STREAM("Expected joint_sign_corrections to contain 6 elements, but it has "
499  << joint_sign_corrections.size() << ".");
500  return false;
501  }
502 
503  for (std::size_t i = 0; i < joint_offsets.size(); ++i)
504  {
505  opw_parameters_.offsets[i] = joint_offsets[i];
506  opw_parameters_.sign_corrections[i] = static_cast<signed char>(joint_sign_corrections[i]);
507  }
508 
509  ROS_INFO_STREAM("Loaded parameters for ik solver:\n" << opw_parameters_);
510 
511  return true;
512 }
513 
514 double MoveItOPWKinematicsPlugin::distance(const std::vector<double>& a, const std::vector<double>& b)
515 {
516  double cost = 0.0;
517  for (size_t i = 0; i < a.size(); ++i)
518  cost += std::abs(b[i] - a[i]);
519  return cost;
520 }
521 
522 // Compute the index of the closest joint pose in 'candidates' from 'target'
523 std::size_t MoveItOPWKinematicsPlugin::closestJointPose(const std::vector<double>& target,
524  const std::vector<std::vector<double>>& candidates)
525 {
526  size_t closest = 0; // index into candidates
527  double lowest_cost = std::numeric_limits<double>::max();
528  for (size_t i = 0; i < candidates.size(); ++i)
529  {
530  assert(target.size() == candidates[i].size());
531  double c = distance(target, candidates[i]);
532  if (c < lowest_cost)
533  {
534  closest = i;
535  lowest_cost = c;
536  }
537  }
538  return closest;
539 }
540 
541 bool MoveItOPWKinematicsPlugin::getAllIK(const Eigen::Affine3d& pose,
542  std::vector<std::vector<double>>& joint_poses) const
543 {
544  joint_poses.clear();
545 
546  // Transform input pose
547  // needed if we introduce a tip frame different from tool0
548  // or a different base frame
549  // Eigen::Affine3d tool_pose = diff_base.inverse() * pose *
550  // tip_frame.inverse();
551 
552  // convert Eigen::Affine3d to Eigen::Isometry3d for opw_kinematics
553  Eigen::Isometry3d pose_isometry;
554  pose_isometry = pose.matrix();
555 
556  std::array<double, 6 * 8> sols;
557  opw_kinematics::inverse(opw_parameters_, pose_isometry, sols.data());
558 
559  // Check the output
560  std::vector<double> tmp(6); // temporary storage for API reasons
561  for (int i = 0; i < 8; i++)
562  {
563  double* sol = sols.data() + 6 * i;
564  if (opw_kinematics::isValid(sol))
565  {
567 
568  // TODO: make this better...
569  std::copy(sol, sol + 6, tmp.data());
570  // if (isValid(tmp))
571  // {
572  joint_poses.push_back(tmp);
573  // }
574  }
575  }
576 
577  return joint_poses.size() > 0;
578 }
579 
580 bool MoveItOPWKinematicsPlugin::getIK(const Eigen::Affine3d& pose, const std::vector<double>& seed_state,
581  std::vector<double>& joint_pose) const
582 {
583  // Descartes Robot Model interface calls for 'closest' point to seed position
584  std::vector<std::vector<double>> joint_poses;
585  if (!getAllIK(pose, joint_poses))
586  return false;
587  // Find closest joint pose; getAllIK() does isValid checks already
588  joint_pose = joint_poses[closestJointPose(seed_state, joint_poses)];
589  return true;
590 }
591 
592 } // namespace moveit_opw_kinematics_plugin
std::vector< unsigned int > redundant_joint_indices_
static std::size_t closestJointPose(const std::vector< double > &target, const std::vector< std::vector< double >> &candidates)
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool selfTest()
check forward and inverse kinematics consistency
bool comparePoses(Eigen::Isometry3d &Ta, Eigen::Affine3d &Tb)
check if two poses are the same within an absolute tolerance of 1e-6
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
bool getIK(const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
const srdf::ModelSharedPtr & getSRDF() const
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
std::vector< std::string > tip_frames_
const double TOLERANCE
#define ROS_INFO_STREAM_NAMED(name, args)
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
bool isValid(const T *qs)
Definition: opw_utilities.h:10
void harmonizeTowardZero(T *qs)
Definition: opw_utilities.h:17
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
#define ROS_DEBUG_NAMED(name,...)
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization) override
bool getAllIK(const Eigen::Affine3d &pose, std::vector< std::vector< double >> &joint_poses) const
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
signed char sign_corrections[6]
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
static double distance(const std::vector< double > &a, const std::vector< double > &b)
bool lookupParam(const std::string &param, T &val, const T &default_val) const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
#define ROS_INFO_STREAM(args)
static WallTime now()
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
#define ROS_ERROR_NAMED(name,...)
bool timedOut(const ros::WallTime &start_time, double duration) const
#define ROS_ERROR_STREAM(args)
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
void inverse(const Parameters< T > &params, const Transform< T > &pose, T *out) noexcept
Computes up to 8 kinematically unique joint solutions that put the tool flange of the robot described...
Transform< T > forward(const Parameters< T > &p, const T *qs) noexcept
Computes the tool pose of the robot described by when said robot has the joint positions given by qs...
CLASS_LOADER_REGISTER_CLASS(Dog, Base)
const urdf::ModelInterfaceSharedPtr & getURDF() const


moveit_opw_kinematics_plugin
Author(s): Jeroen De Maeyer, Simon Schmeisser (isys vision)
autogenerated on Wed Jun 3 2020 03:17:14