Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
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)
00045 , angular_distance_weight_(1.0)
00046 {
00047 type_ = PLANAR;
00048
00049 local_variable_names_.push_back("x");
00050 local_variable_names_.push_back("y");
00051 local_variable_names_.push_back("theta");
00052 for (int i = 0 ; i < 3 ; ++i)
00053 {
00054 variable_names_.push_back(name_ + "/" + local_variable_names_[i]);
00055 variable_index_map_[variable_names_.back()] = i;
00056 }
00057
00058 variable_bounds_.resize(3);
00059 variable_bounds_[0].position_bounded_ = true;
00060 variable_bounds_[1].position_bounded_ = true;
00061 variable_bounds_[2].position_bounded_ = false;
00062
00063 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
00064 variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
00065 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
00066 variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
00067 variable_bounds_[2].min_position_ = -boost::math::constants::pi<double>();
00068 variable_bounds_[2].max_position_ = boost::math::constants::pi<double>();
00069
00070 computeVariableBoundsMsg();
00071 }
00072
00073 unsigned int moveit::core::PlanarJointModel::getStateSpaceDimension() const
00074 {
00075 return 3;
00076 }
00077
00078 double moveit::core::PlanarJointModel::getMaximumExtent(const Bounds &other_bounds) const
00079 {
00080 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
00081 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
00082 return sqrt(dx*dx + dy*dy) + boost::math::constants::pi<double>() * angular_distance_weight_;
00083 }
00084
00085 void moveit::core::PlanarJointModel::getVariableDefaultPositions(double *values, const Bounds &bounds) const
00086 {
00087 for (unsigned int i = 0 ; i < 2 ; ++i)
00088 {
00089
00090 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
00091 values[i] = 0.0;
00092 else
00093 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
00094 }
00095 values[2] = 0.0;
00096 }
00097
00098 void moveit::core::PlanarJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &bounds) const
00099 {
00100 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() || bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
00101 values[0] = 0.0;
00102 else
00103 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
00104 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() || bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
00105 values[1] = 0.0;
00106 else
00107 values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
00108 values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
00109 }
00110
00111 void moveit::core::PlanarJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &bounds,
00112 const double *near, const double distance) const
00113 {
00114 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() || bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
00115 values[0] = 0.0;
00116 else
00117 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
00118 std::min(bounds[0].max_position_, near[0] + distance));
00119 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() || bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
00120 values[1] = 0.0;
00121 else
00122 values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
00123 std::min(bounds[1].max_position_, near[1] + distance));
00124
00125 double da = angular_distance_weight_ * distance;
00126 values[2] = rng.uniformReal(near[2] - da, near[2] + da);
00127 normalizeRotation(values);
00128 }
00129
00130 void moveit::core::PlanarJointModel::interpolate(const double *from, const double *to, const double t, double *state) const
00131 {
00132
00133 state[0] = from[0] + (to[0] - from[0]) * t;
00134 state[1] = from[1] + (to[1] - from[1]) * t;
00135
00136
00137 double diff = to[2] - from[2];
00138 if (fabs(diff) <= boost::math::constants::pi<double>())
00139 state[2] = from[2] + diff * t;
00140 else
00141 {
00142 if (diff > 0.0)
00143 diff = 2.0 * boost::math::constants::pi<double>() - diff;
00144 else
00145 diff = -2.0 * boost::math::constants::pi<double>() - diff;
00146 state[2] = from[2] - diff * t;
00147
00148 if (state[2] > boost::math::constants::pi<double>())
00149 state[2] -= 2.0 * boost::math::constants::pi<double>();
00150 else
00151 if (state[2] < -boost::math::constants::pi<double>())
00152 state[2] += 2.0 * boost::math::constants::pi<double>();
00153 }
00154 }
00155
00156 double moveit::core::PlanarJointModel::distance(const double *values1, const double *values2) const
00157 {
00158 double dx = values1[0] - values2[0];
00159 double dy = values1[1] - values2[1];
00160
00161 double d = fabs(values1[2] - values2[2]);
00162 d = (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
00163 return sqrt(dx*dx + dy*dy) + angular_distance_weight_ * d;
00164 }
00165
00166 bool moveit::core::PlanarJointModel::satisfiesPositionBounds(const double *values, const Bounds &bounds, double margin) const
00167 {
00168 for (unsigned int i = 0 ; i < 3 ; ++i)
00169 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
00170 return false;
00171 return true;
00172 }
00173
00174 bool moveit::core::PlanarJointModel::normalizeRotation(double *values) const
00175 {
00176 double &v = values[2];
00177 if (v >= -boost::math::constants::pi<double>() && v <= boost::math::constants::pi<double>())
00178 return false;
00179 v = fmod(v, 2.0 * boost::math::constants::pi<double>());
00180 if (v < -boost::math::constants::pi<double>())
00181 v += 2.0 * boost::math::constants::pi<double>();
00182 else
00183 if (v > boost::math::constants::pi<double>())
00184 v -= 2.0 * boost::math::constants::pi<double>();
00185 return true;
00186 }
00187
00188 bool moveit::core::PlanarJointModel::enforcePositionBounds(double *values, const Bounds &bounds) const
00189 {
00190 bool result = normalizeRotation(values);
00191 for (unsigned int i = 0 ; i < 2 ; ++i)
00192 {
00193 if (values[i] < bounds[i].min_position_)
00194 {
00195 values[i] = bounds[i].min_position_;
00196 result = true;
00197 }
00198 else
00199 if (values[i] > bounds[i].max_position_)
00200 {
00201 values[i] = bounds[i].max_position_;
00202 result = true;
00203 }
00204 }
00205 return result;
00206 }
00207
00208 void moveit::core::PlanarJointModel::computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
00209 {
00210 transf = Eigen::Affine3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) * Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
00211 }
00212
00213 void moveit::core::PlanarJointModel::computeVariablePositions(const Eigen::Affine3d& transf, double *joint_values) const
00214 {
00215 joint_values[0] = transf.translation().x();
00216 joint_values[1] = transf.translation().y();
00217
00218 Eigen::Quaterniond q(transf.rotation());
00219
00220 double s_squared = 1.0-(q.w()*q.w());
00221 if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
00222 joint_values[2] = 0.0;
00223 else
00224 {
00225 double s = 1.0/sqrt(s_squared);
00226 joint_values[2] = (acos(q.w())*2.0f)*(q.z()*s);
00227 }
00228 }