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/prismatic_joint_model.h>
00038 #include <limits>
00039
00040 moveit::core::PrismaticJointModel::PrismaticJointModel(const std::string& name)
00041 : JointModel(name)
00042 , axis_(0.0, 0.0, 0.0)
00043 {
00044 type_ = PRISMATIC;
00045 variable_names_.push_back(name_);
00046 variable_bounds_.resize(1);
00047 variable_bounds_[0].position_bounded_ = true;
00048 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::max();
00049 variable_bounds_[0].max_position_ = std::numeric_limits<double>::max();
00050 variable_index_map_[name_] = 0;
00051 computeVariableBoundsMsg();
00052 }
00053
00054 unsigned int moveit::core::PrismaticJointModel::getStateSpaceDimension() const
00055 {
00056 return 1;
00057 }
00058
00059 double moveit::core::PrismaticJointModel::getMaximumExtent(const Bounds &other_bounds) const
00060 {
00061 return variable_bounds_[0].max_position_ - other_bounds[0].min_position_;
00062 }
00063
00064 void moveit::core::PrismaticJointModel::getVariableDefaultPositions(double *values, const Bounds &bounds) const
00065 {
00066
00067 if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
00068 values[0] = 0.0;
00069 else
00070 values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
00071 }
00072
00073 bool moveit::core::PrismaticJointModel::satisfiesPositionBounds(const double *values, const Bounds &bounds, double margin) const
00074 {
00075 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
00076 return false;
00077 return true;
00078 }
00079
00080 void moveit::core::PrismaticJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &bounds) const
00081 {
00082 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
00083 }
00084
00085 void moveit::core::PrismaticJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &bounds,
00086 const double *near, const double distance) const
00087 {
00088 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
00089 std::min(bounds[0].max_position_, near[0] + distance));
00090 }
00091
00092 bool moveit::core::PrismaticJointModel::enforcePositionBounds(double *values, const Bounds &bounds) const
00093 {
00094 if (values[0] < bounds[0].min_position_)
00095 {
00096 values[0] = bounds[0].min_position_;
00097 return true;
00098 }
00099 else
00100 if (values[0] > bounds[0].max_position_)
00101 {
00102 values[0] = bounds[0].max_position_;
00103 return true;
00104 }
00105 return false;
00106 }
00107
00108 double moveit::core::PrismaticJointModel::distance(const double *values1, const double *values2) const
00109 {
00110 return fabs(values1[0] - values2[0]);
00111 }
00112
00113 void moveit::core::PrismaticJointModel::interpolate(const double *from, const double *to, const double t, double *state) const
00114 {
00115 state[0] = from[0] + (to[0] - from[0]) * t;
00116 }
00117
00118 void moveit::core::PrismaticJointModel::computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
00119 {
00120 double *d = transf.data();
00121 d[0] = 1.0;
00122 d[1] = 0.0;
00123 d[2] = 0.0;
00124 d[3] = 0.0;
00125
00126 d[4] = 0.0;
00127 d[5] = 1.0;
00128 d[6] = 0.0;
00129 d[7] = 0.0;
00130
00131 d[8] = 0.0;
00132 d[9] = 0.0;
00133 d[10] = 1.0;
00134 d[11] = 0.0;
00135
00136 d[12] = axis_.x() * joint_values[0];
00137 d[13] = axis_.y() * joint_values[0];
00138 d[14] = axis_.z() * joint_values[0];
00139 d[15] = 1.0;
00140
00141
00142
00143 }
00144
00145 void moveit::core::PrismaticJointModel::computeVariablePositions(const Eigen::Affine3d& transf, double *joint_values) const
00146 {
00147 joint_values[0] = transf.translation().dot(axis_);
00148 }