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;
77 return !(values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin);
81 const Bounds& bounds)
const 83 values[0] = rng.
uniformReal(bounds[0].min_position_, bounds[0].max_position_);
87 const Bounds& bounds,
const double* near,
90 values[0] = rng.
uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
91 std::min(bounds[0].max_position_, near[0] + distance));
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]);
116 state[0] = from[0] + (to[0] - from[0]) * t;
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];
148 joint_values[0] = transf.translation().dot(
axis_);
virtual void interpolate(const double *from, const double *to, const double t, double *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.
std::string name_
Name of the joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
JointType type_
The type of joint.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PrismaticJointModel(const std::string &name)
double getMaximumExtent() const
Eigen::Vector3d axis_
The axis of the joint.
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
void computeVariableBoundsMsg()
virtual bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const
Check if the set of position values for the variables of this joint are within bounds, up to some margin.
virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
double uniformReal(double lower_bound, double upper_bound)
virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. Return true if changes were made.
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
virtual void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
virtual double distance(const double *values1, const double *values2) const
Compute the distance between two joint states of the same model (represented by the variable values) ...