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 #include <moveit/robot_model/revolute_joint_model.h>
00038 #include <boost/math/constants/constants.hpp>
00039 #include <limits>
00040 #include <cmath>
00041
00042 robot_model::RevoluteJointModel::RevoluteJointModel(const std::string& name) : JointModel(name),
00043 axis_(0.0, 0.0, 0.0), continuous_(false)
00044 {
00045 type_ = REVOLUTE;
00046 variable_bounds_.push_back(std::make_pair(-boost::math::constants::pi<double>(), boost::math::constants::pi<double>()));
00047 variable_names_.push_back(name_);
00048 }
00049
00050 unsigned int robot_model::RevoluteJointModel::getStateSpaceDimension() const
00051 {
00052 return 1;
00053 }
00054
00055 double robot_model::RevoluteJointModel::getMaximumExtent(const Bounds &other_bounds) const
00056 {
00057 return other_bounds[0].second - other_bounds[0].first;
00058 }
00059
00060 void robot_model::RevoluteJointModel::getVariableDefaultValues(std::vector<double> &values, const Bounds &bounds) const
00061 {
00062
00063 if (bounds[0].first <= 0.0 && bounds[0].second >= 0.0)
00064 values.push_back(0.0);
00065 else
00066 values.push_back((bounds[0].first + bounds[0].second)/2.0);
00067 }
00068
00069 void robot_model::RevoluteJointModel::getVariableRandomValues(random_numbers::RandomNumberGenerator &rng, std::vector<double> &values, const Bounds &bounds) const
00070 {
00071 values.push_back(rng.uniformReal(bounds[0].first, bounds[0].second));
00072 }
00073
00074 void robot_model::RevoluteJointModel::getVariableRandomValuesNearBy(random_numbers::RandomNumberGenerator &rng, std::vector<double> &values, const Bounds &bounds,
00075 const std::vector<double> &near, const double distance) const
00076 {
00077 if (continuous_)
00078 {
00079 values.push_back(rng.uniformReal(near[values.size()] - distance, near[values.size()] + distance));
00080 enforceBounds(values, bounds);
00081 }
00082 else
00083 values.push_back(rng.uniformReal(std::max(bounds[0].first, near[values.size()] - distance),
00084 std::min(bounds[0].second, near[values.size()] + distance)));
00085 }
00086
00087 void robot_model::RevoluteJointModel::interpolate(const std::vector<double> &from, const std::vector<double> &to, const double t, std::vector<double> &state) const
00088 {
00089 if (continuous_)
00090 {
00091 double diff = to[0] - from[0];
00092 if (fabs(diff) <= boost::math::constants::pi<double>())
00093 state[0] = from[0] + diff * t;
00094 else
00095 {
00096 if (diff > 0.0)
00097 diff = 2.0 * boost::math::constants::pi<double>() - diff;
00098 else
00099 diff = -2.0 * boost::math::constants::pi<double>() - diff;
00100 state[0] = from[0] - diff * t;
00101
00102 if (state[0] > boost::math::constants::pi<double>())
00103 state[0] -= 2.0 * boost::math::constants::pi<double>();
00104 else
00105 if (state[0] < -boost::math::constants::pi<double>())
00106 state[0] += 2.0 * boost::math::constants::pi<double>();
00107 }
00108 }
00109 else
00110 state[0] = from[0] + (to[0] - from[0]) * t;
00111 }
00112
00113 double robot_model::RevoluteJointModel::distance(const std::vector<double> &values1, const std::vector<double> &values2) const
00114 {
00115 assert(values1.size() == 1);
00116 assert(values2.size() == 1);
00117 if (continuous_)
00118 {
00119 double d = fabs(values1[0] - values2[0]);
00120 return (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
00121 }
00122 else
00123 return fabs(values1[0] - values2[0]);
00124 }
00125
00126 bool robot_model::RevoluteJointModel::satisfiesBounds(const std::vector<double> &values, const Bounds &bounds, double margin) const
00127 {
00128 if (continuous_)
00129 return true;
00130 assert(bounds.size() > 0);
00131 if (values[0] < bounds[0].first - margin || values[0] > bounds[0].second + margin)
00132 return false;
00133 return true;
00134 }
00135
00136 void robot_model::RevoluteJointModel::enforceBounds(std::vector<double> &values, const Bounds &bounds) const
00137 {
00138 if (continuous_)
00139 {
00140 double &v = values[0];
00141 v = fmod(v, 2.0 * boost::math::constants::pi<double>());
00142 if (v < -boost::math::constants::pi<double>())
00143 v += 2.0 * boost::math::constants::pi<double>();
00144 else
00145 if (v > boost::math::constants::pi<double>())
00146 v -= 2.0 * boost::math::constants::pi<double>();
00147 }
00148 else
00149 {
00150 const std::pair<double, double> &b = bounds[0];
00151 if (values[0] < b.first)
00152 values[0] = b.first;
00153 else
00154 if (values[0] > b.second)
00155 values[0] = b.second;
00156 }
00157 }
00158
00159 void robot_model::RevoluteJointModel::computeDefaultVariableLimits()
00160 {
00161 JointModel::computeDefaultVariableLimits();
00162 if (continuous_)
00163 default_limits_[0].has_position_limits = false;
00164 }
00165
00166 void robot_model::RevoluteJointModel::computeTransform(const std::vector<double>& joint_values, Eigen::Affine3d &transf) const
00167 {
00168 updateTransform(joint_values, transf);
00169 }
00170
00171 void robot_model::RevoluteJointModel::updateTransform(const std::vector<double>& joint_values, Eigen::Affine3d &transf) const
00172 {
00173 transf = Eigen::Affine3d(Eigen::AngleAxisd(joint_values[0], axis_));
00174 }
00175
00176 void robot_model::RevoluteJointModel::computeJointStateValues(const Eigen::Affine3d& transf, std::vector<double> &joint_values) const
00177 {
00178 joint_values.resize(1);
00179 Eigen::Quaterniond q(transf.rotation());
00180 q.normalize();
00181 joint_values[0] = acos(q.w())*2.0f;
00182 }