47 variable_names_.push_back(name_);
48 variable_bounds_.resize(1);
49 variable_bounds_[0].position_bounded_ =
true;
50 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::max();
51 variable_bounds_[0].max_position_ = std::numeric_limits<double>::max();
52 variable_index_map_[name_] = 0;
53 computeVariableBoundsMsg();
56 unsigned int PrismaticJointModel::getStateSpaceDimension()
const
61 double PrismaticJointModel::getMaximumExtent(
const Bounds& other_bounds)
const
63 return variable_bounds_[0].max_position_ - other_bounds[0].min_position_;
66 void PrismaticJointModel::getVariableDefaultPositions(
double* values,
const Bounds& bounds)
const
69 if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
72 values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
75 bool PrismaticJointModel::satisfiesPositionBounds(
const double* values,
const Bounds& bounds,
double margin)
const
77 return !(
values[0] < bounds[0].min_position_ - margin ||
values[0] > bounds[0].max_position_ + margin);
81 const Bounds& bounds)
const
87 const Bounds& bounds,
const double* seed,
91 std::min(bounds[0].max_position_, seed[0] +
distance));
94 bool PrismaticJointModel::enforcePositionBounds(
double* values,
const Bounds& bounds)
const
96 if (values[0] < bounds[0].min_position_)
98 values[0] = bounds[0].min_position_;
101 else if (values[0] > bounds[0].max_position_)
103 values[0] = bounds[0].max_position_;
111 return fabs(values1[0] - values2[0]);
114 void PrismaticJointModel::interpolate(
const double* from,
const double* to,
const double t,
double* state)
const
116 state[0] = from[0] + (to[0] - from[0]) * t;
119 void PrismaticJointModel::computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
const
121 double*
d = transf.data();
137 d[12] = axis_.x() * joint_values[0];
138 d[13] = axis_.y() * joint_values[0];
139 d[14] = axis_.z() * joint_values[0];
146 void PrismaticJointModel::computeVariablePositions(
const Eigen::Isometry3d& transf,
double* joint_values)
const
148 joint_values[0] = transf.translation().dot(axis_);