Classes | Functions
mpc_local_planner Namespace Reference

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...
 

Function Documentation

◆ average_angles()

double mpc_local_planner::average_angles ( const std::vector< double > &  angles)
inline

Return the average angle of an arbitrary number of given angles [rad].

Parameters
anglesvector containing all angles
Returns
average / mean angle, that is normalized to [-pi, pi]

Definition at line 55 of file math_utils.h.

◆ convert()

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>.

Remarks
Note, the actual data of the TimeSeries object is copied without interpolation.
Todo:
We could avoid the system dynamics dependency by specifying a generic getter function for the SE2 poses
Parameters
[in]time_seriescorbo::TimeSeries object or any child class
[in]dynamicsReference to the robot dynamics interface (to access state-to-SE2 conversion methods)
[out]poses_stampedThe resulting pose array (note, the incoming vector will be cleared)
[in]frame_idThe planning frame id that is added to the message header

Definition at line 49 of file conversion.cpp.

◆ cross2d()

template<typename V1 , typename V2 >
double mpc_local_planner::cross2d ( const V1 &  v1,
const V2 &  v2 
)
inline

Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d)

Parameters
v1object containing public methods x() and y()
v2object containing fields x() and y()
Returns
magnitude that would result in the 3D case (along the z-axis)

Definition at line 91 of file math_utils.h.

◆ distance_points2d() [1/2]

template<typename P1 , typename P2 >
double mpc_local_planner::distance_points2d ( const P1 &  point1,
const P2 &  point2 
)
inline

Calculate Euclidean distance between two 2D point datatypes.

Parameters
point1object containing fields x and y
point2object containing fields x and y
Returns
Euclidean distance: ||point2-point1||

Definition at line 76 of file math_utils.h.

◆ distance_points2d() [2/2]

double mpc_local_planner::distance_points2d ( double  x1,
double  y1,
double  x2,
double  y2 
)
inline

Calculate Euclidean distance between two 2D points.

Definition at line 82 of file math_utils.h.

◆ interpolate_angle()

double mpc_local_planner::interpolate_angle ( double  angle1,
double  angle2,
double  factor 
)
inline

Return the interpolated angle between two angles [rad].

Parameters
angle1
angle2
factorin [0,1], or (1,inf) for extrapolation
Returns
average / mean angle, that is normalized to [-pi, pi]

Definition at line 120 of file math_utils.h.

◆ normalize_theta()

double mpc_local_planner::normalize_theta ( double  theta)
inline

normalize angle to interval [-pi, pi)

Remarks
This function is based on normalize_theta from g2o see: https://github.com/RainerKuemmerle/g2o/blob/master/g2o/stuff/misc.h

Definition at line 101 of file math_utils.h.



mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06