selfdriving
Namespaces | Classes | Typedefs | Enumerations | Functions
mpp Namespace Reference

Namespaces

 ptg
 

Classes

class  CostEvaluator
 
class  CostEvaluatorCostMap
 
class  CostEvaluatorPreferredWaypoint
 
struct  EnqueuedCondition
 
struct  EnqueuedMotionCmd
 
class  LidarSource
 
class  MotionPrimitivesTree
 
struct  MoveEdgeSE2_TPS
 
class  MVSIM_VehicleInterface
 
class  NavEngine
 
struct  NavErrorReason
 
class  ObstacleSource
 
class  ObstacleSourceGenericSensor
 
class  ObstacleSourceStaticPointcloud
 
class  Planner
 
struct  PlannerInput
 
struct  PlannerOutput
 
struct  PoseDistanceMetric_Lie
 
struct  PoseDistanceMetric_Lie< SE2_KinState >
 
struct  PoseDistanceMetric_TPS
 
struct  PoseDistanceMetric_TPS< SE2_KinState >
 
struct  PoseOrPoint
 
struct  ProgressCallbackData
 
struct  RenderOptions
 
struct  RenderVehicleExtraResults
 
struct  RenderVehicleParams
 
struct  SE2_KinState
 
struct  SE2orR2_KinState
 
class  TargetApproachController
 
struct  TargetApproachInput
 
struct  TargetApproachOutput
 
class  TPS_Astar
 
struct  TPS_Astar_Parameters
 
struct  TPS_point
 
class  TrajectoriesAndRobotShape
 
struct  trajectory_state_t
 
struct  VehicleLocalizationState
 
class  VehicleMotionInterface
 
struct  VehicleOdometryState
 
struct  VisualizationOptions
 
struct  Waypoint
 
struct  WaypointSequence
 
struct  WaypointsRenderingParams
 
struct  WaypointStatus
 
struct  WaypointStatusSequence
 

Typedefs

using astar_heuristic_t = std::function< cost_t(const SE2_KinState &, const SE2orR2_KinState &)>
 
using distance_t = double
 
using normalized_distance_t = double
 
using ptg_step_t = uint32_t
 
using cost_t = double
 
using trajectory_index_t = int
 
using ptg_index_t = size_t
 
using normalized_speed_t = double
 
using duration_seconds_t = double
 
template<typename T >
using const_ref_t = std::optional< std::reference_wrapper< const T > >
 
using MotionPrimitivesTreeSE2 = MotionPrimitivesTree< SE2_KinState, MoveEdgeSE2_TPS >
 
using planner_progress_callback_t = std::function< void(const ProgressCallbackData &)>
 
using ptg_t = mrpt::nav::CParameterizedTrajectoryGenerator
 
using robot_radius_t = double
 
using RobotShape = std::variant< mrpt::math::TPolygon2D, robot_radius_t, std::monostate >
 
using trajectory_t = std::map< duration_seconds_t, trajectory_state_t >
 
using waypoint_idx_t = std::size_t
 

Enumerations

enum  NavStatus : uint8_t { NavStatus::IDLE = 0, NavStatus::NAVIGATING, NavStatus::SUSPENDED, NavStatus::NAV_ERROR }
 
enum  NavError : uint8_t { NavError::NONE = 0, NavError::EMERGENCY_STOP, NavError::CANNOT_REACH_TARGET, NavError::OTHER }
 
enum  STOP_TYPE : uint8_t { STOP_TYPE::REGULAR = 0, STOP_TYPE::EMERGENCY }
 

Functions

bool bestTrajectory (MoveEdgeSE2_TPS &npa, const TrajectoriesAndRobotShape &trs, std::optional< mrpt::system::COutputLogger *> logger=std::nullopt)
 
void edge_interpolated_path (MoveEdgeSE2_TPS &edge, const TrajectoriesAndRobotShape &trs, const std::optional< mrpt::math::TPose2D > &reconstrRelPoseOpt=std::nullopt, const std::optional< size_t > &ptg_stepOpt=std::nullopt, const std::optional< size_t > &numSegments=std::nullopt)
 
void refine_trajectory (const MotionPrimitivesTreeSE2::path_t &inPath, MotionPrimitivesTreeSE2::edge_sequence_t &edgesToRefine, const TrajectoriesAndRobotShape &ptgInfo)
 
void refine_trajectory (const std::vector< MotionPrimitivesTreeSE2::node_t > &inPath, std::vector< MotionPrimitivesTreeSE2::edge_t > &edgesToRefine, const TrajectoriesAndRobotShape &ptgInfo)
 
auto render_tree (const MotionPrimitivesTreeSE2 &tree, const PlannerInput &pi, const RenderOptions &ro) -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
 
auto render_vehicle (const RobotShape &rs, mrpt::opengl::CSetOfLines &outPolygon, const RenderVehicleParams &rvp={}) -> RenderVehicleExtraResults
 
distance_t tp_obstacles_single_path (const trajectory_index_t tp_space_k_direction, const mrpt::maps::CPointsMap &localObstacles, const ptg_t &ptg)
 
trajectory_t plan_to_trajectory (const MotionPrimitivesTreeSE2::edge_sequence_t &planEdges, const TrajectoriesAndRobotShape &ptgInfo, const duration_seconds_t samplePeriod=50e-3)
 
bool save_to_txt (const trajectory_t &traj, const std::string &fileName)
 
void transform_pc_square_clipping (const mrpt::maps::CPointsMap &inMap, const mrpt::poses::CPose2D &asSeenFrom, const double MAX_DIST_XY, mrpt::maps::CPointsMap &outMap, bool appendToOutMap=true)
 
void viz_nav_plan (const PlannerOutput &plan, const VisualizationOptions &opts={}, const std::vector< CostEvaluator::Ptr > costEvaluators={})
 
void viz_nav_plan_animation (const PlannerOutput &plan, const mpp::trajectory_t &traj, const RenderOptions &opts={}, const std::vector< CostEvaluator::Ptr > costEvaluators={})
 
bool operator< (const TPS_point &a, const TPS_point &b)
 
bool obstaclePointCollides (const mrpt::math::TPoint2D &obstacleWrtRobot, const TrajectoriesAndRobotShape &trs)
 

Typedef Documentation

◆ astar_heuristic_t

using mpp::astar_heuristic_t = typedef std::function<cost_t( const SE2_KinState& , const SE2orR2_KinState& )>

◆ const_ref_t

template<typename T >
using mpp::const_ref_t = typedef std::optional<std::reference_wrapper<const T> >

Wrapper to a const reference to T

◆ cost_t

using mpp::cost_t = typedef double

Cost of a given trajectory or trajectory segment

◆ distance_t

using mpp::distance_t = typedef double

Distances measured by PoseDistanceMetric, or "pseudodistances" of PTGs, that is, distances along SE(2), including a weighted distance for rotations

◆ duration_seconds_t

using mpp::duration_seconds_t = typedef double

Time duration in seconds

◆ MotionPrimitivesTreeSE2

tree data structure for planning in SE2 within TP-Space manifolds

◆ normalized_distance_t

using mpp::normalized_distance_t = typedef double

TPS normalized distances in range [0,1]

◆ normalized_speed_t

using mpp::normalized_speed_t = typedef double

Normalized (or relative) speed in range [0,1]

◆ planner_progress_callback_t

using mpp::planner_progress_callback_t = typedef std::function<void(const ProgressCallbackData&)>

◆ ptg_index_t

using mpp::ptg_index_t = typedef size_t

◆ ptg_step_t

using mpp::ptg_step_t = typedef uint32_t

TPS discrete time steps

◆ ptg_t

using mpp::ptg_t = typedef mrpt::nav::CParameterizedTrajectoryGenerator

◆ robot_radius_t

using mpp::robot_radius_t = typedef double

◆ RobotShape

using mpp::RobotShape = typedef std::variant<mrpt::math::TPolygon2D, robot_radius_t, std::monostate>

◆ trajectory_index_t

using mpp::trajectory_index_t = typedef int

Index of a trajectory in a PTG

◆ trajectory_t

◆ waypoint_idx_t

using mpp::waypoint_idx_t = typedef std::size_t

Enumeration Type Documentation

◆ NavError

enum mpp::NavError : uint8_t
strong

Explains the reason for the navigation error.

Enumerator
NONE 
EMERGENCY_STOP 
CANNOT_REACH_TARGET 
OTHER 

◆ NavStatus

enum mpp::NavStatus : uint8_t
strong

The different statuses for the navigation system.

Enumerator
IDLE 
NAVIGATING 
SUSPENDED 
NAV_ERROR 

◆ STOP_TYPE

enum mpp::STOP_TYPE : uint8_t
strong
Enumerator
REGULAR 
EMERGENCY 

Function Documentation

◆ bestTrajectory()

bool mpp::bestTrajectory ( MoveEdgeSE2_TPS npa,
const TrajectoriesAndRobotShape trs,
std::optional< mrpt::system::COutputLogger *>  logger = std::nullopt 
)

Finds the best trajectory between two kinematic states, given the set of feasible trajectories.

Returns
true on success, false on no valid path found

◆ edge_interpolated_path()

void mpp::edge_interpolated_path ( MoveEdgeSE2_TPS edge,
const TrajectoriesAndRobotShape trs,
const std::optional< mrpt::math::TPose2D > &  reconstrRelPoseOpt = std::nullopt,
const std::optional< size_t > &  ptg_stepOpt = std::nullopt,
const std::optional< size_t > &  numSegments = std::nullopt 
)

◆ obstaclePointCollides()

bool mpp::obstaclePointCollides ( const mrpt::math::TPoint2D &  obstacleWrtRobot,
const TrajectoriesAndRobotShape trs 
)

◆ operator<()

bool mpp::operator< ( const TPS_point a,
const TPS_point b 
)
inline

◆ plan_to_trajectory()

trajectory_t mpp::plan_to_trajectory ( const MotionPrimitivesTreeSE2::edge_sequence_t planEdges,
const TrajectoriesAndRobotShape ptgInfo,
const duration_seconds_t  samplePeriod = 50e-3 
)

◆ refine_trajectory() [1/2]

void mpp::refine_trajectory ( const MotionPrimitivesTreeSE2::path_t inPath,
MotionPrimitivesTreeSE2::edge_sequence_t edgesToRefine,
const TrajectoriesAndRobotShape ptgInfo 
)

Takes a sequence of N states (the inPath) and the N-1 edges in between them, and recalculate the PTG parameters of all edges using the exact poses in the path nodes.

◆ refine_trajectory() [2/2]

void mpp::refine_trajectory ( const std::vector< MotionPrimitivesTreeSE2::node_t > &  inPath,
std::vector< MotionPrimitivesTreeSE2::edge_t > &  edgesToRefine,
const TrajectoriesAndRobotShape ptgInfo 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ render_tree()

auto mpp::render_tree ( const MotionPrimitivesTreeSE2 tree,
const PlannerInput pi,
const RenderOptions ro 
) -> std::shared_ptr< mrpt::opengl::CSetOfObjects >

Gets a CSetOfObjects::Ptr visual representation of a motion tree

◆ render_vehicle()

auto mpp::render_vehicle ( const RobotShape rs,
mrpt::opengl::CSetOfLines &  outPolygon,
const RenderVehicleParams rvp = {} 
) -> RenderVehicleExtraResults

Generates a polygon for the vehicle shape

◆ save_to_txt()

bool mpp::save_to_txt ( const trajectory_t traj,
const std::string &  fileName 
)

◆ tp_obstacles_single_path()

distance_t mpp::tp_obstacles_single_path ( const trajectory_index_t  tp_space_k_direction,
const mrpt::maps::CPointsMap &  localObstacles,
const ptg_t ptg 
)

Returns TPS-distance (pseudometers, not normalized) to obstacles. ptg dynamic state must be updated by the caller.

◆ transform_pc_square_clipping()

void mpp::transform_pc_square_clipping ( const mrpt::maps::CPointsMap &  inMap,
const mrpt::poses::CPose2D &  asSeenFrom,
const double  MAX_DIST_XY,
mrpt::maps::CPointsMap &  outMap,
bool  appendToOutMap = true 
)

Returns local obstacles as seen from a given pose, clipped to a maximum distance.

◆ viz_nav_plan()

void mpp::viz_nav_plan ( const PlannerOutput plan,
const VisualizationOptions opts = {},
const std::vector< CostEvaluator::Ptr >  costEvaluators = {} 
)

◆ viz_nav_plan_animation()

void mpp::viz_nav_plan_animation ( const PlannerOutput plan,
const mpp::trajectory_t traj,
const RenderOptions opts = {},
const std::vector< CostEvaluator::Ptr >  costEvaluators = {} 
)