utils.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/kinematic_constraints/utils.h>
00038 #include <shape_tools/solid_primitive_dims.h>
00039 
00040 moveit_msgs::Constraints kinematic_constraints::mergeConstraints(const moveit_msgs::Constraints &first, const moveit_msgs::Constraints &second)
00041 {
00042   moveit_msgs::Constraints r;
00043 
00044   // add all joint constraints that are in first but not in second
00045   // and merge joint constraints that are for the same joint
00046   for (std::size_t i = 0 ; i < first.joint_constraints.size() ; ++i)
00047   {
00048     bool add = true;
00049     for (std::size_t j = 0 ; j < second.joint_constraints.size() ; ++j)
00050       if (second.joint_constraints[j].joint_name == first.joint_constraints[i].joint_name)
00051       {
00052         add = false;
00053         // now we merge
00054         moveit_msgs::JointConstraint m;
00055         const moveit_msgs::JointConstraint &a = first.joint_constraints[i];
00056         const moveit_msgs::JointConstraint &b = second.joint_constraints[j];
00057         double low = std::max(a.position - a.tolerance_below, b.position - b.tolerance_below);
00058         double high = std::min(a.position + a.tolerance_above, b.position + b.tolerance_above);
00059         if (low > high)
00060           logError("Attempted to merge incompatible constraints for joint '%s'. Discarding constraint.", a.joint_name.c_str());
00061         else
00062         {
00063           m.joint_name = a.joint_name;
00064           m.position = std::max(low, std::min((a.position * a.weight + b.position * b.weight) / (a.weight + b.weight), high));
00065           m.weight = (a.weight + b.weight) / 2.0;
00066           m.tolerance_above = std::max(0.0, high - m.position);
00067           m.tolerance_below = std::max(0.0, m.position - low);
00068           r.joint_constraints.push_back(m);
00069         }
00070         break;
00071       }
00072     if (add)
00073       r.joint_constraints.push_back(first.joint_constraints[i]);
00074   }
00075 
00076   // add all joint constraints that are in second but not in first
00077   for (std::size_t i = 0 ; i < second.joint_constraints.size() ; ++i)
00078   {
00079     bool add = true;
00080     for (std::size_t j = 0 ; j < first.joint_constraints.size() ; ++j)
00081       if (second.joint_constraints[i].joint_name == first.joint_constraints[j].joint_name)
00082       {
00083         add = false;
00084         break;
00085       }
00086     if (add)
00087       r.joint_constraints.push_back(second.joint_constraints[i]);
00088   }
00089 
00090   // merge rest of constraints
00091   r.position_constraints = first.position_constraints;
00092   for (std::size_t i = 0 ; i < second.position_constraints.size() ; ++i)
00093     r.position_constraints.push_back(second.position_constraints[i]);
00094 
00095   r.orientation_constraints = first.orientation_constraints;
00096   for (std::size_t i = 0 ; i < second.orientation_constraints.size() ; ++i)
00097     r.orientation_constraints.push_back(second.orientation_constraints[i]);
00098 
00099   r.visibility_constraints = first.visibility_constraints;
00100   for (std::size_t i = 0 ; i < second.visibility_constraints.size() ; ++i)
00101     r.visibility_constraints.push_back(second.visibility_constraints[i]);
00102 
00103   return r;
00104 }
00105 
00106 bool kinematic_constraints::isEmpty(const moveit_msgs::Constraints &constr)
00107 {
00108   return constr.position_constraints.empty() && constr.orientation_constraints.empty() &&
00109     constr.visibility_constraints.empty() && constr.joint_constraints.empty();
00110 }
00111 
00112 std::size_t kinematic_constraints::countIndividualConstraints(const moveit_msgs::Constraints &constr)
00113 {
00114   return constr.position_constraints.size() + constr.orientation_constraints.size() +
00115     constr.visibility_constraints.size() + constr.joint_constraints.size();
00116 }
00117 
00118 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const robot_state::JointStateGroup *jsg,
00119                                                                          double tolerance)
00120 {
00121   return constructGoalConstraints(jsg, tolerance, tolerance);
00122 }
00123 
00124 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const robot_state::JointStateGroup *jsg,
00125                                                                          double tolerance_below, double tolerance_above)
00126 {
00127   moveit_msgs::Constraints goal;
00128 
00129   std::map<std::string, double> vals;
00130   jsg->getVariableValues(vals);
00131 
00132   goal.joint_constraints.resize(vals.size());
00133   unsigned int i = 0;
00134   for (std::map<std::string, double>::iterator it = vals.begin() ; it != vals.end(); ++it, ++i)
00135   {
00136     goal.joint_constraints[i].joint_name = it->first;
00137     goal.joint_constraints[i].position = it->second;
00138     goal.joint_constraints[i].tolerance_above = tolerance_below;
00139     goal.joint_constraints[i].tolerance_below = tolerance_above;
00140     goal.joint_constraints[i].weight = 1.0;
00141   }
00142 
00143   return goal;
00144 }
00145 
00146 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const std::string &link_name, const geometry_msgs::PoseStamped &pose,
00147                                                                          double tolerance_pos, double tolerance_angle)
00148 {
00149   moveit_msgs::Constraints goal;
00150 
00151   goal.position_constraints.resize(1);
00152   moveit_msgs::PositionConstraint &pcm = goal.position_constraints[0];
00153   pcm.link_name = link_name;
00154   pcm.target_point_offset.x = 0;
00155   pcm.target_point_offset.y = 0;
00156   pcm.target_point_offset.z = 0;
00157   pcm.constraint_region.primitives.resize(1);
00158   shape_msgs::SolidPrimitive &bv = pcm.constraint_region.primitives[0];
00159   bv.type = shape_msgs::SolidPrimitive::SPHERE;
00160   bv.dimensions.resize(shape_tools::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::SPHERE>::value);
00161   bv.dimensions[shape_msgs::SolidPrimitive::SPHERE_RADIUS] = tolerance_pos;
00162 
00163   pcm.header = pose.header;
00164   pcm.constraint_region.primitive_poses.resize(1);
00165   pcm.constraint_region.primitive_poses[0].position = pose.pose.position;
00166 
00167   // orientation of constraint region does not affect anything, since it is a sphere
00168   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00169   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00170   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00171   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00172   pcm.weight = 1.0;
00173 
00174   goal.orientation_constraints.resize(1);
00175   moveit_msgs::OrientationConstraint &ocm = goal.orientation_constraints[0];
00176   ocm.link_name = link_name;
00177   ocm.header = pose.header;
00178   ocm.orientation = pose.pose.orientation;
00179   ocm.absolute_x_axis_tolerance = tolerance_angle;
00180   ocm.absolute_y_axis_tolerance = tolerance_angle;
00181   ocm.absolute_z_axis_tolerance = tolerance_angle;
00182   ocm.weight = 1.0;
00183 
00184   return goal;
00185 }
00186 
00187 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const std::string &link_name, const geometry_msgs::PoseStamped &pose,
00188                                                                          const std::vector<double> &tolerance_pos, const std::vector<double> &tolerance_angle)
00189 {
00190   moveit_msgs::Constraints goal = constructGoalConstraints(link_name, pose);
00191   if (tolerance_pos.size() == 3)
00192   {
00193     shape_msgs::SolidPrimitive &bv = goal.position_constraints[0].constraint_region.primitives[0];
00194     bv.type = shape_msgs::SolidPrimitive::BOX;
00195     bv.dimensions.resize(shape_tools::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00196     bv.dimensions[shape_msgs::SolidPrimitive::BOX_X] = tolerance_pos[0];
00197     bv.dimensions[shape_msgs::SolidPrimitive::BOX_Y] = tolerance_pos[1];
00198     bv.dimensions[shape_msgs::SolidPrimitive::BOX_Z] = tolerance_pos[2];
00199   }
00200   if (tolerance_angle.size() == 3)
00201   {
00202     moveit_msgs::OrientationConstraint &ocm = goal.orientation_constraints[0];
00203     ocm.absolute_x_axis_tolerance = tolerance_angle[0];
00204     ocm.absolute_y_axis_tolerance = tolerance_angle[1];
00205     ocm.absolute_z_axis_tolerance = tolerance_angle[2];
00206   }
00207   return goal;
00208 }
00209 
00210 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const std::string &link_name, const geometry_msgs::QuaternionStamped &quat, double tolerance)
00211 {
00212   moveit_msgs::Constraints goal;
00213   goal.orientation_constraints.resize(1);
00214   moveit_msgs::OrientationConstraint &ocm = goal.orientation_constraints[0];
00215   ocm.link_name = link_name;
00216   ocm.header = quat.header;
00217   ocm.orientation = quat.quaternion;
00218   ocm.absolute_x_axis_tolerance = tolerance;
00219   ocm.absolute_y_axis_tolerance = tolerance;
00220   ocm.absolute_z_axis_tolerance = tolerance;
00221   ocm.weight = 1.0;
00222   return goal;
00223 }
00224 
00225 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const std::string &link_name, const geometry_msgs::PointStamped &goal_point, double tolerance)
00226 {
00227   geometry_msgs::Point p;
00228   p.x = 0;
00229   p.y = 0;
00230   p.z = 0;
00231   return constructGoalConstraints(link_name, p, goal_point, tolerance );
00232 }
00233 
00234 moveit_msgs::Constraints kinematic_constraints::constructGoalConstraints(const std::string &link_name, const geometry_msgs::Point &reference_point, const geometry_msgs::PointStamped &goal_point, double tolerance)
00235 {
00236   moveit_msgs::Constraints goal;
00237   goal.position_constraints.resize(1);
00238   moveit_msgs::PositionConstraint &pcm = goal.position_constraints[0];
00239   pcm.link_name = link_name;
00240   pcm.target_point_offset.x = reference_point.x;
00241   pcm.target_point_offset.y = reference_point.y;
00242   pcm.target_point_offset.z = reference_point.z;
00243   pcm.constraint_region.primitives.resize(1);
00244   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00245   pcm.constraint_region.primitives[0].dimensions.resize(shape_tools::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::SPHERE>::value);
00246   pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::SPHERE_RADIUS] = tolerance;
00247 
00248   pcm.header = goal_point.header;
00249   pcm.constraint_region.primitive_poses.resize(1);
00250   pcm.constraint_region.primitive_poses[0].position = goal_point.point;
00251 
00252   // orientation of constraint region does not affect anything, since it is a sphere
00253   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00254   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00255   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00256   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00257   pcm.weight = 1.0;
00258 
00259   return goal;
00260 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:47