ikfast_plugin.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 #include <ros/ros.h>
00019 
00020 #include <moveit/kinematics_base/kinematics_base.h>
00021 
00022 #include <tf_conversions/tf_kdl.h>
00023 
00024 #define IKFAST_HAS_LIBRARY
00025 #define IKFAST_NO_MAIN
00026 #include "ikfast.h"
00027 
00028 #include <moveit_msgs/GetKinematicSolverInfo.h>
00029 #include <moveit_msgs/MoveItErrorCodes.h>
00030 #include <urdf/model.h>
00031 
00032 void print_frame(const char * str, const double* trans, const double* rot) {
00033     ROS_ERROR("%s %f %f %f, %f %f %f %f %f %f %f %f %f", str, trans[0], trans[1], trans[2], rot[0],  rot[1], rot[2], rot[3], rot[4], rot[5], rot[6], rot[7], rot[8]);
00034 }
00035 void setConsistencyLimit(std::vector<std::pair<double, double> > &min_max,
00036         const std::vector<double> &seed, const std::vector<double> &consistency_limits) {
00037     if(min_max.size() != seed.size() || min_max.size() != consistency_limits.size()) return;
00038 
00039     for(unsigned int i=0; i <min_max.size(); ++i){
00040         min_max[i].first = fmax(min_max[i].first, seed[i] - consistency_limits[i]);
00041         min_max[i].second = fmin(min_max[i].second, seed[i] + consistency_limits[i]);
00042     }
00043 }
00044 
00045 struct Stepper {
00046     int upper_, lower_, current_;
00047     double *value;
00048     double start_, step_;
00049     Stepper(double *value, double lower, double upper, double step) :
00050         current_(0), value(value), start_(*value), step_(step) {
00051         double right_bound = fmax(lower, start_ - M_PI) + 2 * M_PI + step;
00052         double left_bound = fmin(upper, start_ + M_PI) - 2 * M_PI - step;
00053         right_bound = fmin(right_bound, upper);
00054         left_bound = fmax(left_bound, lower);
00055 
00056         lower_ = -(int) (fabs(left_bound - start_) / step);
00057         upper_ = fabs(right_bound - start_) / step;
00058         //ROS_ERROR("Stepper: %f %f %f %f, %d %d", *value, lower, upper, step, lower_, upper_);
00059     }
00060     void reset() {
00061         current_ = 0;
00062         *value = start_;
00063     }
00064     bool step() {
00065         int next;
00066         if (current_ <= 0) { // neg
00067             next = 1 - current_; // -> pos
00068             if (next > upper_) {
00069                 next = -next; // -> neg
00070                 if (next < lower_) return false;
00071             }
00072         } else { // pos
00073             next = -current_; // -> neg
00074             if (next < lower_) {
00075                 next = 1 - next; // -> pos
00076                 if (next > upper_) return false;
00077             }
00078 
00079         }
00080         current_ = next;
00081         *value = start_ + current_ * step_;
00082         return true;
00083     }
00084 };
00085 
00086 struct JointSpaceStepper {
00087     std::vector<Stepper> steppers;
00088     int current_;
00089     std::vector<double> state;
00090     JointSpaceStepper(double step, const std::vector<double> &ik_seed_state,
00091             const std::vector<std::pair<double, double> > &min_max,
00092             const std::vector<double> &indices) :
00093         current_(0), state(indices.size()) {
00094         int i = 0;
00095         for (std::vector<double>::const_reverse_iterator it = indices.rbegin(); it
00096                 != indices.rend(); ++it) { // reverse!
00097             steppers.push_back(Stepper(&state[i++], min_max[*it].first,
00098                     min_max[*it].second, step));
00099         }
00100     }
00101     bool step() {
00102         bool overflow = false;
00103         while (current_ < steppers.size() && !steppers[current_].step()) {
00104             ++current_;
00105             overflow = true;
00106         }
00107         if (current_ >= steppers.size()) return false;
00108         if (overflow) {
00109             while (current_ > 0)
00110                 steppers[current_--].reset();
00111         }
00112         return true;
00113 
00114     }
00115 };
00116 
00117 using namespace ikfast;
00118 
00119 template<class A1, class A2>
00120 std::ostream& operator<<(std::ostream& s, std::vector<A1, A2> const& vec)
00121 {
00122     copy(vec.begin(), vec.end(), std::ostream_iterator<A1>(s, " "));
00123     return s;
00124 }
00125 
00126 class IkSolutionListFiltered: public IkSolutionList<double> {
00127 protected:
00128     const std::vector<std::pair<double, double> > &min_max;
00129     const std::vector<double> &ik_seed_state;
00130     const kinematics::KinematicsBase::IKCallbackFn &solution_callback;
00131     const geometry_msgs::Pose &ik_pose;
00132     double min_dist;
00133     std::vector<double> min_solution;
00134 
00135     virtual bool filterSolution(const std::vector<double> &values) {
00136         for (unsigned int i = 0; i < min_max.size(); ++i)
00137             if (values[i] < min_max[i].first || values[i] > min_max[i].second) {
00138                 return false;
00139             }
00140 
00141         moveit_msgs::MoveItErrorCodes error_code;
00142         error_code.val = error_code.SUCCESS;
00143         if (solution_callback) solution_callback(ik_pose, values, error_code);
00144         return error_code.val == error_code.SUCCESS;
00145     }
00146     double  ik_values[12];
00147 public:
00148     IkSolutionListFiltered(
00149             const std::vector<std::pair<double, double> > &min_max,
00150             const std::vector<double> &ik_seed_state,
00151             const kinematics::KinematicsBase::IKCallbackFn  &solution_callback,
00152             const geometry_msgs::Pose &ik_pose) :
00153         min_max(min_max), ik_seed_state(ik_seed_state), solution_callback(
00154                 solution_callback), ik_pose(ik_pose) {
00155         KDL::Frame frame;
00156         tf::poseMsgToKDL(ik_pose, frame);
00157         ik_values[0] = frame.p[0]; ik_values[1] = frame.p[1];  ik_values[2] = frame.p[2];
00158         ik_values[3] = frame.M.data[0]; ik_values[4] = frame.M.data[1]; ik_values[5] = frame.M.data[2];
00159         ik_values[6] = frame.M.data[3]; ik_values[7] = frame.M.data[4]; ik_values[8] = frame.M.data[5];
00160         ik_values[9] = frame.M.data[6]; ik_values[10] = frame.M.data[7]; ik_values[11] = frame.M.data[8];
00161     }
00162 
00163     virtual size_t AddSolution(const std::vector<
00164             IkSingleDOFSolutionBase<double> >& vinfos,
00165             const std::vector<int>& vfree) {
00166 
00167         //ROS_ERROR("Solution!");
00168 
00169         IkSolution<double> sol(vinfos, vfree);
00170         std::vector<double> vsolfree(sol.GetFree().size());
00171         std::vector<double> solvalues;
00172         sol.GetSolution(solvalues, vsolfree);
00173 
00174 
00175         double dist = harmonize(ik_seed_state, solvalues, min_max);
00176         if (filterSolution(solvalues)) {
00177             if (min_solution.empty() || dist < min_dist) min_solution
00178                     = solvalues;
00179         }
00180 
00181         return IkSolutionList<double>::AddSolution(vinfos, vfree);
00182     }
00183     static double harmonize(const std::vector<double> &ik_seed_state,
00184             std::vector<double> &solution, const std::vector<std::pair<double, double> > &min_max) {
00185         double dist_sqr = 0;
00186         for (size_t i = 0; i < solution.size(); ++i) {
00187             if (fabs(solution[i] - ik_seed_state[i]) > M_PI) {
00188                 if (ik_seed_state[i] < solution[i]) {
00189                     if (solution[i] > 0 && solution[i] - 2 * M_PI >= min_max[i].first) solution[i] -= 2 * M_PI;
00190                 } else {
00191                     if (solution[i] < 0  && solution[i] + 2 * M_PI <= min_max[i].second) solution[i] += 2 * M_PI;
00192                 }
00193             }
00194 
00195             dist_sqr += fabs(solution[i] - ik_seed_state[i]);
00196         }
00197         return dist_sqr;
00198     }
00199 
00200     bool getMinSolution(std::vector<double> &dest) {
00201         if (min_solution.empty()) return false;
00202         dest = min_solution;
00203         return true;
00204     }
00205 };
00206 namespace IKFAST_NAMESPACE {
00207 
00208 class IKFastPlugin: public kinematics::KinematicsBase {
00209 public:
00217     virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00218                                 const std::vector<double> &ik_seed_state,
00219                                 std::vector<double> &solution,
00220                                 moveit_msgs::MoveItErrorCodes &error_code,
00221                                 const kinematics::KinematicsQueryOptions &options) const {
00222 
00223         return searchPositionIK(ik_pose, ik_seed_state, solution, min_max_,
00224                 error_code);
00225     }
00226 
00235     virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00236                                    const std::vector<double> &ik_seed_state,
00237                                    double timeout,
00238                                    std::vector<double> &solution,
00239                                    moveit_msgs::MoveItErrorCodes &error_code,
00240                                    const kinematics::KinematicsQueryOptions &options) const {
00241 
00242         return searchPositionIK(ik_pose, ik_seed_state, solution, min_max_,
00243                 error_code, timeout);
00244     }
00245 
00255     virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00256                                    const std::vector<double> &ik_seed_state,
00257                                    double timeout,
00258                                    const std::vector<double> &consistency_limits,
00259                                    std::vector<double> &solution,
00260                                    moveit_msgs::MoveItErrorCodes &error_code,
00261                                    const kinematics::KinematicsQueryOptions &options) const {
00262 
00263         std::vector<std::pair<double, double> > min_max = min_max_;
00264         setConsistencyLimit(min_max, ik_seed_state, consistency_limits);
00265         return searchPositionIK(ik_pose, ik_seed_state, solution, min_max,
00266                 error_code, timeout);
00267     }
00268 
00277     virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00278                                    const std::vector<double> &ik_seed_state,
00279                                    double timeout,
00280                                    std::vector<double> &solution,
00281                                    const IKCallbackFn &solution_callback,
00282                                    moveit_msgs::MoveItErrorCodes &error_code,
00283                                    const kinematics::KinematicsQueryOptions &options) const {
00284 
00285         return searchPositionIK(ik_pose, ik_seed_state, solution, min_max_,
00286                 error_code, timeout, solution_callback);
00287     }
00288 
00299     virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00300                                    const std::vector<double> &ik_seed_state,
00301                                    double timeout,
00302                                    const std::vector<double> &consistency_limits,
00303                                    std::vector<double> &solution,
00304                                    const IKCallbackFn &solution_callback,
00305                                    moveit_msgs::MoveItErrorCodes &error_code,
00306                                    const kinematics::KinematicsQueryOptions &options) const {
00307 
00308         std::vector<std::pair<double, double> > min_max = min_max_;
00309         setConsistencyLimit(min_max, ik_seed_state, consistency_limits);
00310         return searchPositionIK(ik_pose, ik_seed_state, solution, min_max,
00311                 error_code, timeout, solution_callback);
00312     }
00313 
00320         virtual bool getPositionFK(const std::vector<std::string> &link_names,
00321                              const std::vector<double> &joint_angles,
00322                              std::vector<geometry_msgs::Pose> &poses) const {
00323         KDL::Frame p_out;
00324 
00325         if (joint_angles.size() != GetNumJoints()) {
00326             ROS_ERROR("%d joint angles are required", GetNumJoints());
00327             return false;
00328         }
00329 
00330         if (link_names.size() != 1 || link_names[0] != tip_frame_) {
00331             ROS_ERROR("Can compute FK for %s only",tip_frame_.c_str());
00332             return false;
00333         }
00334 
00335         ComputeFk(&joint_angles[0], p_out.p.data, p_out.M.data);
00336         // print_frame("FK:", p_out.p.data, p_out.M.data);
00337         poses.resize(1);
00338         tf::poseKDLToMsg(p_out, poses[0]);
00339         return true;
00340     }
00341 
00346     virtual bool initialize(const std::string& robot_description,
00347                           const std::string& group_name,
00348                           const std::string& base_frame,
00349                           const std::string& tip_frame,
00350                           double search_discretization){
00351         setValues(robot_description, group_name, base_frame, tip_frame, search_discretization);
00352 
00353         links_.resize(1);
00354         links_[0] = tip_frame_;
00355 
00356         // Load and Read Models
00357         if (!loadModel(robot_description)) {
00358             ROS_FATAL("Could not load models!");
00359             return false;
00360         }
00361         indices_.clear();
00362         for (int i = 0; i < GetNumFreeParameters(); ++i)
00363             indices_.push_back(GetFreeParameters()[i]);
00364         return true;
00365     }
00366 
00370     virtual const std::vector<std::string>& getJointNames() const {
00371         return joints_;
00372     }
00373 
00377     virtual const std::vector<std::string>& getLinkNames() const {
00378         return links_;
00379     }
00380 
00384     virtual ~IKFastPlugin() {
00385     }
00386     IKFastPlugin() :
00387         bounds_epsilon_(0.0) {
00388     }
00389 protected:
00390     std::vector<std::pair<double, double> > min_max_;
00391     double bounds_epsilon_;
00392     std::vector<double> indices_;
00393     std::vector<std::string> links_;
00394     std::vector<std::string> joints_;
00395     bool searchPositionIK(
00396             const geometry_msgs::Pose &ik_pose,
00397             const std::vector<double> &ik_seed_state,
00398             std::vector<double> &solution,
00399             const std::vector<std::pair<double, double> > &min_max,
00400             moveit_msgs::MoveItErrorCodes &error_code,
00401             const double timeout = -1,
00402             const IKCallbackFn &solution_callback = 0) const {
00403 
00404         KDL::Frame frame;
00405         tf::poseMsgToKDL(ik_pose, frame);
00406         error_code.val = error_code.NO_IK_SOLUTION;
00407 
00408                 if(ik_seed_state.size() < GetNumJoints()){
00409             ROS_ERROR_STREAM("Needs " << GetNumJoints() << "joint values. but only " << ik_seed_state.size() << "were given.");
00410                 return false;
00411                 }
00412 
00413         // print_frame("IK:", frame.p.data, frame.M.data);
00414         JointSpaceStepper jss(search_discretization_, ik_seed_state, min_max,
00415                 indices_);
00416 
00417         IkSolutionListFiltered sollist(min_max, ik_seed_state,
00418                 solution_callback, ik_pose);
00419 
00420         ros::Time maxTime = ros::Time::now() + ros::Duration(timeout);
00421         do {
00422             //ROS_ERROR("State: %f", jss.state[0]);
00423             if (ComputeIk(frame.p.data, frame.M.data, indices_.empty()?0:&jss.state[0], sollist)) {
00424                 error_code.val = error_code.START_STATE_IN_COLLISION; // is reachable but violates constraints
00425             }
00426             if (sollist.getMinSolution(solution)) {
00427                 error_code.val = error_code.SUCCESS;
00428                 break;
00429             }
00430             if (timeout >= 0.0 && ros::Time::now() > maxTime) {
00431                 error_code.val = error_code.TIMED_OUT;
00432                 break;
00433             }
00434         } while (jss.step());
00435         return error_code.val == error_code.SUCCESS;
00436     }
00437     bool loadModel(const std::string param) {
00438         urdf::Model robot_model;
00439 
00440         if (!robot_model.initParam(param)) {
00441             ROS_FATAL("Could not initialize robot model");
00442             return false;
00443         }
00444         if (!readJoints(robot_model)) {
00445             ROS_FATAL("Could not read information about the joints");
00446             return false;
00447         }
00448         return true;
00449     }
00450 
00451     bool readJoints(urdf::Model &robot_model) {
00452         int dimension_ = 0;
00453         // get joint maxs and mins
00454         boost::shared_ptr<const urdf::Link> link = robot_model.getLink(
00455                 tip_frame_);
00456         boost::shared_ptr<const urdf::Joint> joint;
00457         while (link && link->name != base_frame_) {
00458             joint = robot_model.getJoint(link->parent_joint->name);
00459             if (!joint) {
00460                 ROS_ERROR("Could not find joint: %s",link->parent_joint->name.c_str());
00461                 return false;
00462             }
00463             if (joint->type != urdf::Joint::UNKNOWN && joint->type
00464                     != urdf::Joint::FIXED) {
00465                 ROS_INFO( "adding joint: [%s]", joint->name.c_str() );
00466                 dimension_++;
00467             }
00468             link = robot_model.getLink(link->getParent()->name);
00469         }
00470 
00471         if (dimension_ != GetNumJoints()) {
00472             ROS_ERROR("Solver needs %d joints, but %d were found.",GetNumJoints(), dimension_);
00473             return false;
00474         }
00475 
00476         min_max_.resize(dimension_);
00477         joints_.resize(dimension_);
00478         link = robot_model.getLink(tip_frame_);
00479 
00480         unsigned int i = 0;
00481         while (link && i < dimension_) {
00482             joint = robot_model.getJoint(link->parent_joint->name);
00483             if (joint->type != urdf::Joint::UNKNOWN && joint->type
00484                     != urdf::Joint::FIXED) {
00485                 ROS_INFO( "getting bounds for joint: [%s]", joint->name.c_str() );
00486 
00487                 float lower, upper;
00488                 if (joint->type != urdf::Joint::CONTINUOUS) {
00489                     if (joint->safety) {
00490                         lower = joint->safety->soft_lower_limit
00491                                 + bounds_epsilon_;
00492                         upper = joint->safety->soft_upper_limit
00493                                 - bounds_epsilon_;
00494                     } else {
00495                         lower = joint->limits->lower + bounds_epsilon_;
00496                         upper = joint->limits->upper - bounds_epsilon_;
00497                     }
00498                 } else {
00499                     lower = -M_PI;
00500                     upper = M_PI;
00501                 }
00502                 min_max_[dimension_ - i - 1] = std::make_pair(lower, upper);
00503                 joints_[dimension_ - i - 1] = joint->name;
00504                 i++;
00505             }
00506             link = robot_model.getLink(link->getParent()->name);
00507         }
00508 
00509         return true;
00510     }
00511 };
00512 
00513 }
00514 #include <pluginlib/class_list_macros.h>
00515 
00516 #define ADD_TYPED_PLUGIN(type,name) PLUGINLIB_DECLARE_CLASS(cob_kinematics, type##name, IKFAST_NAMESPACE::IKFastPlugin, kinematics::KinematicsBase)
00517 #define ADD_IKFAST_PLUGIN(name) ADD_TYPED_PLUGIN(IKFast_, name)
00518 ADD_IKFAST_PLUGIN(IKFAST_NAMESPACE)
00519 ;
00520 


cob_kinematics
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 21:22:52