Loading...
Searching...
No Matches
OwenStateSpace.cpp
107std::optional<OwenStateSpace::PathType> OwenStateSpace::getPath(const State *state1, const State *state2) const
124 { return (dubinsSpace_.getPath(state1, state2, r).length() + twopi * k) * r * tanMaxPitch_ - std::abs(dz); };
126 auto result = boost::math::tools::bracket_and_solve_root(radiusFun, radius, 2., true, TOLERANCE, iter);
128 // Discontinuities in the Dubins distance and, by extension, radiusFun can cause bracket_and_solve_root to fail.
142 return (std::abs(phi) + dubinsSpace_.getPath(zi, state2).length()) * rho_ * tanMaxPitch_ - std::abs(dz);
148 auto result = boost::math::tools::bracket_and_solve_root(phiFun, phi, 2., true, TOLERANCE, iter);
176void OwenStateSpace::turn(const State *from, double turnRadius, double angle, State *state) const
181 s1->setXY(s0->getX() + r * (std::sin(phi) - std::sin(theta)), s0->getY() + r * (-std::cos(phi) + std::cos(theta)));
197void OwenStateSpace::interpolate(const State *from, const State *to, double t, State *state) const
205void OwenStateSpace::interpolate(const State *from, const State *to, double t, PathType &path, State *state) const
237 dubinsSpace_.interpolate(from, path.path_, (dist - lengthSpiral) / lengthPath, state, path.turnRadius_);
252 dubinsSpace_.interpolate(s, path.path_, (dist - lengthTurn) / lengthPath, state, path.turnRadius_);
265 getSubspace(1)->enforceBounds(state->as<CompoundStateSpace::StateType>()->as<SO2StateSpace::StateType>(1));
299 << "\n\tturnRadius=" << path.turnRadius_ << "\n\tdeltaZ=" << path.deltaZ_ << "\n\tphi=" << path.phi_
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition StateSpace.h:577
unsigned int getDimension() const override
Get the dimension of the space (not the dimension of the surrounding ambient space).
Definition StateSpace.cpp:994
const StateSpacePtr & getSubspace(unsigned int index) const
Get a specific subspace from the compound state space.
Definition StateSpace.cpp:915
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces.
Definition StateSpace.cpp:1153
double getMaximumExtent() const override
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
Definition StateSpace.cpp:1002
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
Definition StateSpace.cpp:1036
const T * as(unsigned int index) const
Cast a component of this instance to a desired type.
Definition State.h:95
An SE(2) state space where distance is measured by the length of Dubins curves.
Definition DubinsStateSpace.h:63
unsigned int validSegmentCount(const State *state1, const State *state2) const override
Count how many segments of the "longest valid length" fit on the motion from state1 to state2....
Definition OwenStateSpace.cpp:192
double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition OwenStateSpace.cpp:185
void interpolate(const State *from, const State *to, double t, State *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
Definition OwenStateSpace.cpp:197
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
Definition OwenStateSpace.cpp:74
DubinsStateSpace dubinsSpace_
Definition OwenStateSpace.h:222
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition OwenStateSpace.h:152
std::optional< PathType > getPath(const State *state1, const State *state2) const
Compute a 3D Dubins path using the model and algorithm proposed by Owen et al.
Definition OwenStateSpace.cpp:107
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition OwenStateSpace.cpp:67
void turn(const State *from, double turnRadius, double angle, State *state) const
Compute the SE(2) state after making a turn.
Definition OwenStateSpace.cpp:176
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
Definition ProjectionEvaluator.h:131
The definition of a state in Rn.
Definition RealVectorStateSpace.h:78
double getYaw() const
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
Definition SE2StateSpace.h:73
void setYaw(double yaw)
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
Definition SE2StateSpace.h:100
The definition of a state in SO(2).
Definition SO2StateSpace.h:68
Representation of a space in which planning can be performed. Topology specific sampling,...
Definition StateSpace.h:71
virtual unsigned int validSegmentCount(const State *state1, const State *state2) const
Count how many segments of the "longest valid length" fit on the motion from state1 to state2.
Definition StateSpace.cpp:851
void registerDefaultProjection(const ProjectionEvaluatorPtr &projection)
Register the default projection for this state space.
Definition StateSpace.cpp:752
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
std::ostream & operator<<(std::ostream &stream, Cost c)
Output operator for Cost.
Definition Cost.cpp:39
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
Definition MagicConstants.h:55
STL namespace.