68 double x = (c1.
xc + c2.
xc) / 2;
69 double y = (c1.
yc + c2.
yc) / 2;
99 TT_tangent_circles(c1, c2, q);
116 return (distance >= 2 * c1.
radius);
134 return TiST_exists(c1, c2) || TeST_exists(c1, c2);
148 theta = angle +
alpha;
156 theta = angle -
alpha;
164 theta = angle -
alpha;
172 theta = angle +
alpha;
219 TiST_tangent_circles(c1, c2, q1, q2);
225 TeST_tangent_circles(c1, c2, q1, q2);
231 if (TiST_exists(c1, c2))
233 return TiST_path(c1, c2, q1, q2);
235 if (TeST_exists(c1, c2))
237 return TeST_path(c1, c2, q1, q2);
239 return numeric_limits<double>::max();
253 return distance <= 4 * c1.
radius;
259 double theta = angle;
261 double delta_x = 0.5 * distance;
262 double delta_y =
sqrt(
pow(r, 2) -
pow(delta_x, 2));
270 TT_tangent_circles(c1, tgt1, q1);
271 TT_tangent_circles(tgt1, c2, q2);
272 TT_tangent_circles(c1, tgt2, q3);
273 TT_tangent_circles(tgt2, c2, q4);
280 TTT_tangent_circles(c1, c2, &qa, &qb, &qc, &qd);
288 if (length1 < length2)
308 return numeric_limits<double>::max();
314 CC00_Dubins_State_Space::CC00_Dubins_State_Space(
double kappa,
double sigma,
double discretization,
bool forwards)
316 , forwards_(forwards)
317 , cc00_dubins_{ unique_ptr<CC00_Dubins>(
new CC00_Dubins(
this)) }
382 &qi1[cc_dubins::TST], &qi2[cc_dubins::TST]);
390 &qi1[cc_dubins::TTT], &qi2[cc_dubins::TTT], &ci1[cc_dubins::TTT]);
397 nullptr, cstart[best_path], cend[best_path], ci1[best_path],
nullptr, length[best_path]);
440 double lg[] = { numeric_limits<double>::max(), numeric_limits<double>::max(), numeric_limits<double>::max(),
441 numeric_limits<double>::max() };
443 for (
int i = 0; i < 2; i++)
445 for (
int j = 0; j < 2; j++)
450 lg[2 * i + j] = path[2 * i + j]->
length;
473 for (
int i = 0; i < 2; i++)
475 delete start_circle[i];
476 delete end_circle[i];
478 for (
int i = 0; i < 4; i++)
485 return path[best_path];
498 vector<Control> cc_dubins_controls;
499 cc_dubins_controls.reserve(9);
531 return cc_dubins_controls;
double get_epsilon()
Return value of epsilon.
CC_Dubins_Path * cc00_circles_dubins_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
Returns a sequence of turns and straight lines connecting the two circles c1 and c2.
bool left
Turning direction: left/right.
double center_distance(const HC_CC_Circle &c1, const HC_CC_Circle &c2)
Cartesian distance between the centers of two circles.
const int nb_cc_dubins_paths
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
void TiST_tangent_circles(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2) const
double sin_mu
Sine and cosine of mu.
double kappa_
Curvature, sharpness of clothoid.
void pointer_array_init(void *array[], int size)
Initialize an array with nullptr.
double cc_turn_length(const Configuration &q) const
Length of a cc-turn.
double TiST_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2) const
bool configuration_on_hc_cc_circle(const HC_CC_Circle &c, const Configuration &q)
Configuration on the circle?
int array_index_min(double array[], int size)
Find index with minimal value in double array.
double radius
Radius of the outer circle.
std::unique_ptr< CC00_Dubins > cc00_dubins_
Pimpl Idiom: unique pointer on class with families.
bool regular
Type of the circle: regular/irregular.
HC_CC_Circle_Param hc_cc_circle_param_
Parameters of a hc-/cc-circle.
double configuration_distance(const Configuration &q1, const Configuration &q2)
Cartesian distance between two configurations.
void cc_turn_controls(const HC_CC_Circle &c, const Configuration &q, bool order, std::vector< Control > &controls)
Appends controls with a cc-turn.
Configuration start
Start and end configuration.
void TTT_tangent_circles(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2, Configuration **q3, Configuration **q4) const
double TTT_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2, HC_CC_Circle **ci) const
CC00_Dubins_State_Space * parent_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
HC_CC_Circle * cstart
Start, end and intermediate circles.
void straight_controls(const Configuration &q1, const Configuration &q2, std::vector< Control > &controls)
Appends controls with a straight line.
double distance(double x0, double y0, double x1, double y1)
void double_array_init(double array[], int size, double value)
Initialize an array with a given value.
double x
Position in x of the robot.
bool configuration_equal(const Configuration &q1, const Configuration &q2)
Are two configurations equal?
double length
Path length.
double TeST_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2) const
bool TT_exists(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
Configuration * qi1
Intermediate configurations.
double TT_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q) const
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
void global_frame_change(double x, double y, double theta, double local_x, double local_y, double *global_x, double *global_y)
Transformation of (local_x, local_y) from local coordinate system to global one.
double TST_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2) const
bool forward
Driving direction: forwards/backwards.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
CC00_Dubins(CC00_Dubins_State_Space *parent)
cc_dubins::path_type type
Path type.
bool TeST_exists(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
Description of a kinematic car's state.
bool TTT_exists(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
void TT_tangent_circles(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q) const
double mu
Angle between the initial orientation and the tangent to the circle at the initial position...
bool TiST_exists(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
CC_Dubins_Path * cc00_dubins(const State &state1, const State &state2) const
Returns a sequence of turns and straight lines connecting a start and an end configuration.
bool configuration_aligned(const Configuration &q1, const Configuration &q2)
Are two configurations aligned?
void TeST_tangent_circles(const HC_CC_Circle &c1, const HC_CC_Circle &c2, Configuration **q1, Configuration **q2) const
An implementation of continuous curvature (CC) steer for a Dubins car with zero curvature at the star...
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void empty_controls(std::vector< Control > &controls)
Appends controls with 0 input.
bool forwards_
Driving direction.
bool TST_exists(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
~CC00_Dubins_State_Space()
Destructor.
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Configuration start
Start configuration.
double xc
Center of the circle.
double y
Position in y of the robot.
double theta
Orientation of the robot.