39 #include <boost/math/constants/constants.hpp> 54 for (
int i = 0; i < 3; ++i)
65 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
67 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
82 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
83 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
89 for (
unsigned int i = 0; i < 2; ++i)
92 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
95 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
101 const Bounds& bounds)
const 103 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
104 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
107 values[0] = rng.
uniformReal(bounds[0].min_position_, bounds[0].max_position_);
108 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
109 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
112 values[1] = rng.
uniformReal(bounds[1].min_position_, bounds[1].max_position_);
113 values[2] = rng.
uniformReal(bounds[2].min_position_, bounds[2].max_position_);
117 const Bounds& bounds,
const double* near,
120 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
121 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
124 values[0] = rng.
uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
125 std::min(bounds[0].max_position_, near[0] + distance));
126 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
127 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
130 values[1] = rng.
uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
131 std::min(bounds[1].max_position_, near[1] + distance));
135 if (da > boost::math::constants::pi<double>())
136 da = boost::math::constants::pi<double>();
137 values[2] = rng.
uniformReal(near[2] - da, near[2] + da);
144 state[0] = from[0] + (to[0] - from[0]) * t;
145 state[1] = from[1] + (to[1] - from[1]) * t;
148 double diff = to[2] - from[2];
149 if (fabs(diff) <= boost::math::constants::pi<double>())
150 state[2] = from[2] + diff * t;
154 diff = 2.0 * boost::math::constants::pi<double>() - diff;
156 diff = -2.0 * boost::math::constants::pi<double>() - diff;
157 state[2] = from[2] - diff * t;
159 if (state[2] > boost::math::constants::pi<double>())
160 state[2] -= 2.0 * boost::math::constants::pi<double>();
161 else if (state[2] < -boost::math::constants::pi<double>())
162 state[2] += 2.0 * boost::math::constants::pi<double>();
168 double dx = values1[0] - values2[0];
169 double dy = values1[1] - values2[1];
171 double d = fabs(values1[2] - values2[2]);
172 d = (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
178 for (
unsigned int i = 0; i < 3; ++i)
179 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
186 double& v = values[2];
187 if (v >= -boost::math::constants::pi<double>() && v <= boost::math::constants::pi<double>())
189 v = fmod(v, 2.0 * boost::math::constants::pi<double>());
190 if (v < -boost::math::constants::pi<double>())
191 v += 2.0 * boost::math::constants::pi<double>();
192 else if (v > boost::math::constants::pi<double>())
193 v -= 2.0 * boost::math::constants::pi<double>();
200 for (
unsigned int i = 0; i < 2; ++i)
202 if (values[i] < bounds[i].min_position_)
204 values[i] = bounds[i].min_position_;
207 else if (values[i] > bounds[i].max_position_)
209 values[i] = bounds[i].max_position_;
218 transf = Eigen::Affine3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) *
219 Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
224 joint_values[0] = transf.translation().x();
225 joint_values[1] = transf.translation().y();
227 Eigen::Quaterniond q(transf.linear());
229 double s_squared = 1.0 - (q.w() * q.w());
230 if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
231 joint_values[2] = 0.0;
234 double s = 1.0 /
sqrt(s_squared);
235 joint_values[2] = (
acos(q.w()) * 2.0
f) * (q.z() * s);
PlanarJointModel(const std::string &name)
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
std::string name_
Name of the joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
JointType type_
The type of joint.
double getMaximumExtent() const
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 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 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.
void computeVariableBoundsMsg()
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 ...
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...
double uniformReal(double lower_bound, double upper_bound)
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
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) ...
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
double angular_distance_weight_
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 ...
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
bool normalizeRotation(double *values) const
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.