Classes | |
class | BaseRobotSE2 |
Specialization of RobotDynamicsInterface for mobile robots operating in SE2. More... | |
class | Controller |
MPC controller for mobile robots. More... | |
class | CrankNicolsonDiffCollocationSE2 |
Collocation via Crank-Nicolson differences (specialized for SE2) More... | |
class | FiniteDifferencesGridSE2 |
Finite differences grid for SE2. More... | |
class | FiniteDifferencesVariableGridSE2 |
Finite differences grid with variable resolution for SE2. More... | |
class | ForwardDiffCollocationSE2 |
Collocation via forward differences (specialized for SE2) More... | |
class | FullDiscretizationGridBaseSE2 |
Full discretization grid specialization for SE2. More... | |
class | KinematicBicycleModelVelocityInput |
Kinematic Bicycle Model with Velocity Input. More... | |
class | MidpointDiffCollocationSE2 |
Collocation via midpoint differences (specialized for SE2) More... | |
class | MinTimeViaPointsCost |
Hybrid cost function with minimum time and via-point objectives. More... | |
class | MpcLocalPlannerROS |
Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract interfaces, so the teb_local_planner plugin can be used both in move_base and move_base_flex (MBF). More... | |
class | PartiallyFixedVectorVertexSE2 |
VectorVertexSE2 with support for partially fixed components. More... | |
class | Publisher |
This class provides publishing methods for common messages. More... | |
class | QuadraticFinalStateCostSE2 |
Quadratic final state cost (specialized for SE2) More... | |
class | QuadraticFormCostSE2 |
Quadratic form running cost (specialized for SE2) More... | |
class | QuadraticStateCostSE2 |
Quadratic state running cost (specialized for SE2) More... | |
class | RobotDynamicsInterface |
Specialization of SystemDynamicsInterface for mobile robots. More... | |
class | SimpleCarFrontWheelDrivingModel |
Simple car model with front wheel actuation. More... | |
class | SimpleCarModel |
Simple car model. More... | |
class | StageInequalitySE2 |
Stage inequality constraint for obstacle avoidance and control deviation limits. More... | |
class | TerminalBallSE2 |
Terminal ball constraint (specialized for SE2) More... | |
class | TimeSeriesSE2 |
Time Series with SE2 support. More... | |
class | UnicycleModel |
Unicycle model. More... | |
class | VectorVertexSE2 |
Vertex specialization for vectors in SE2. More... | |
Functions | |
double | average_angles (const std::vector< double > &angles) |
Return the average angle of an arbitrary number of given angles [rad]. More... | |
void | convert (const corbo::TimeSeries &time_series, const RobotDynamicsInterface &dynamics, std::vector< geometry_msgs::PoseStamped > &poses_stamped, const std::string &frame_id) |
Convert TimeSeries to pose array. More... | |
template<typename V1 , typename V2 > | |
double | cross2d (const V1 &v1, const V2 &v2) |
Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d) More... | |
template<typename P1 , typename P2 > | |
double | distance_points2d (const P1 &point1, const P2 &point2) |
Calculate Euclidean distance between two 2D point datatypes. More... | |
double | distance_points2d (double x1, double y1, double x2, double y2) |
Calculate Euclidean distance between two 2D points. More... | |
double | interpolate_angle (double angle1, double angle2, double factor) |
Return the interpolated angle between two angles [rad]. More... | |
double | normalize_theta (double theta) |
normalize angle to interval [-pi, pi) More... | |
|
inline |
Return the average angle of an arbitrary number of given angles [rad].
angles | vector containing all angles |
Definition at line 55 of file math_utils.h.
void mpc_local_planner::convert | ( | const corbo::TimeSeries & | time_series, |
const RobotDynamicsInterface & | dynamics, | ||
std::vector< geometry_msgs::PoseStamped > & | poses_stamped, | ||
const std::string & | frame_id | ||
) |
Convert TimeSeries to pose array.
Converts TimeSeries to std::vector<geometry_msgs::PoseStamped>.
[in] | time_series | corbo::TimeSeries object or any child class |
[in] | dynamics | Reference to the robot dynamics interface (to access state-to-SE2 conversion methods) |
[out] | poses_stamped | The resulting pose array (note, the incoming vector will be cleared) |
[in] | frame_id | The planning frame id that is added to the message header |
Definition at line 49 of file conversion.cpp.
|
inline |
Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d)
Definition at line 91 of file math_utils.h.
|
inline |
Calculate Euclidean distance between two 2D point datatypes.
point1 | object containing fields x and y |
point2 | object containing fields x and y |
Definition at line 76 of file math_utils.h.
|
inline |
Calculate Euclidean distance between two 2D points.
Definition at line 82 of file math_utils.h.
|
inline |
Return the interpolated angle between two angles [rad].
angle1 | |
angle2 | |
factor | in [0,1], or (1,inf) for extrapolation |
Definition at line 120 of file math_utils.h.
|
inline |
normalize angle to interval [-pi, pi)
Definition at line 101 of file math_utils.h.