planar_joint_model.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2013, Ioan A. Sucan
00005 *  Copyright (c) 2008-2013, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 /* Author: Ioan Sucan */
00037 
00038 #include <moveit/robot_model/planar_joint_model.h>
00039 #include <boost/math/constants/constants.hpp>
00040 #include <limits>
00041 #include <cmath>
00042 
00043 moveit::core::PlanarJointModel::PlanarJointModel(const std::string& name)
00044   : JointModel(name), angular_distance_weight_(1.0)
00045 {
00046   type_ = PLANAR;
00047 
00048   local_variable_names_.push_back("x");
00049   local_variable_names_.push_back("y");
00050   local_variable_names_.push_back("theta");
00051   for (int i = 0; i < 3; ++i)
00052   {
00053     variable_names_.push_back(name_ + "/" + local_variable_names_[i]);
00054     variable_index_map_[variable_names_.back()] = i;
00055   }
00056 
00057   variable_bounds_.resize(3);
00058   variable_bounds_[0].position_bounded_ = true;
00059   variable_bounds_[1].position_bounded_ = true;
00060   variable_bounds_[2].position_bounded_ = false;
00061 
00062   variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
00063   variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
00064   variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
00065   variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
00066   variable_bounds_[2].min_position_ = -boost::math::constants::pi<double>();
00067   variable_bounds_[2].max_position_ = boost::math::constants::pi<double>();
00068 
00069   computeVariableBoundsMsg();
00070 }
00071 
00072 unsigned int moveit::core::PlanarJointModel::getStateSpaceDimension() const
00073 {
00074   return 3;
00075 }
00076 
00077 double moveit::core::PlanarJointModel::getMaximumExtent(const Bounds& other_bounds) const
00078 {
00079   double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
00080   double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
00081   return sqrt(dx * dx + dy * dy) + boost::math::constants::pi<double>() * angular_distance_weight_;
00082 }
00083 
00084 void moveit::core::PlanarJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
00085 {
00086   for (unsigned int i = 0; i < 2; ++i)
00087   {
00088     // if zero is a valid value
00089     if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
00090       values[i] = 0.0;
00091     else
00092       values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
00093   }
00094   values[2] = 0.0;
00095 }
00096 
00097 void moveit::core::PlanarJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng,
00098                                                                 double* values, const Bounds& bounds) const
00099 {
00100   if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
00101       bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
00102     values[0] = 0.0;
00103   else
00104     values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
00105   if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
00106       bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
00107     values[1] = 0.0;
00108   else
00109     values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
00110   values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
00111 }
00112 
00113 void moveit::core::PlanarJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng,
00114                                                                       double* values, const Bounds& bounds,
00115                                                                       const double* near, const double distance) const
00116 {
00117   if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
00118       bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
00119     values[0] = 0.0;
00120   else
00121     values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
00122                                 std::min(bounds[0].max_position_, near[0] + distance));
00123   if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
00124       bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
00125     values[1] = 0.0;
00126   else
00127     values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
00128                                 std::min(bounds[1].max_position_, near[1] + distance));
00129 
00130   double da = angular_distance_weight_ * distance;
00131   // limit the sampling range to 2pi to work correctly even if the distance is very large
00132   if (da > boost::math::constants::pi<double>())
00133     da = boost::math::constants::pi<double>();
00134   values[2] = rng.uniformReal(near[2] - da, near[2] + da);
00135   normalizeRotation(values);
00136 }
00137 
00138 void moveit::core::PlanarJointModel::interpolate(const double* from, const double* to, const double t,
00139                                                  double* state) const
00140 {
00141   // interpolate position
00142   state[0] = from[0] + (to[0] - from[0]) * t;
00143   state[1] = from[1] + (to[1] - from[1]) * t;
00144 
00145   // interpolate angle
00146   double diff = to[2] - from[2];
00147   if (fabs(diff) <= boost::math::constants::pi<double>())
00148     state[2] = from[2] + diff * t;
00149   else
00150   {
00151     if (diff > 0.0)
00152       diff = 2.0 * boost::math::constants::pi<double>() - diff;
00153     else
00154       diff = -2.0 * boost::math::constants::pi<double>() - diff;
00155     state[2] = from[2] - diff * t;
00156     // input states are within bounds, so the following check is sufficient
00157     if (state[2] > boost::math::constants::pi<double>())
00158       state[2] -= 2.0 * boost::math::constants::pi<double>();
00159     else if (state[2] < -boost::math::constants::pi<double>())
00160       state[2] += 2.0 * boost::math::constants::pi<double>();
00161   }
00162 }
00163 
00164 double moveit::core::PlanarJointModel::distance(const double* values1, const double* values2) const
00165 {
00166   double dx = values1[0] - values2[0];
00167   double dy = values1[1] - values2[1];
00168 
00169   double d = fabs(values1[2] - values2[2]);
00170   d = (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
00171   return sqrt(dx * dx + dy * dy) + angular_distance_weight_ * d;
00172 }
00173 
00174 bool moveit::core::PlanarJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds,
00175                                                              double margin) const
00176 {
00177   for (unsigned int i = 0; i < 3; ++i)
00178     if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
00179       return false;
00180   return true;
00181 }
00182 
00183 bool moveit::core::PlanarJointModel::normalizeRotation(double* values) const
00184 {
00185   double& v = values[2];
00186   if (v >= -boost::math::constants::pi<double>() && v <= boost::math::constants::pi<double>())
00187     return false;
00188   v = fmod(v, 2.0 * boost::math::constants::pi<double>());
00189   if (v < -boost::math::constants::pi<double>())
00190     v += 2.0 * boost::math::constants::pi<double>();
00191   else if (v > boost::math::constants::pi<double>())
00192     v -= 2.0 * boost::math::constants::pi<double>();
00193   return true;
00194 }
00195 
00196 bool moveit::core::PlanarJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
00197 {
00198   bool result = normalizeRotation(values);
00199   for (unsigned int i = 0; i < 2; ++i)
00200   {
00201     if (values[i] < bounds[i].min_position_)
00202     {
00203       values[i] = bounds[i].min_position_;
00204       result = true;
00205     }
00206     else if (values[i] > bounds[i].max_position_)
00207     {
00208       values[i] = bounds[i].max_position_;
00209       result = true;
00210     }
00211   }
00212   return result;
00213 }
00214 
00215 void moveit::core::PlanarJointModel::computeTransform(const double* joint_values, Eigen::Affine3d& transf) const
00216 {
00217   transf = Eigen::Affine3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) *
00218                            Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
00219 }
00220 
00221 void moveit::core::PlanarJointModel::computeVariablePositions(const Eigen::Affine3d& transf, double* joint_values) const
00222 {
00223   joint_values[0] = transf.translation().x();
00224   joint_values[1] = transf.translation().y();
00225 
00226   Eigen::Quaterniond q(transf.rotation());
00227   // taken from Bullet
00228   double s_squared = 1.0 - (q.w() * q.w());
00229   if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
00230     joint_values[2] = 0.0;
00231   else
00232   {
00233     double s = 1.0 / sqrt(s_squared);
00234     joint_values[2] = (acos(q.w()) * 2.0f) * (q.z() * s);
00235   }
00236 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49