maliput_sparse
geometry.h File Reference
#include <optional>
#include "maliput_sparse/geometry/line_string.h"
Include dependency graph for geometry.h:
This graph shows which files directly or indirectly include this file:

Classes

struct  BoundPointsResult
 Holds the result of GetBoundPointsAtP method. More...
 
struct  ClosestPointToSegmentResult< CoordinateT >
 Holds the result of GetClosestPointToSegment method. More...
 
struct  ClosestPointResult< CoordinateT >
 Holds the result of GetClosestPoint method. More...
 

Namespaces

 maliput_sparse
 
 maliput_sparse::geometry
 
 maliput_sparse::geometry::utility
 

Typedefs

using ClosestPointResult3d = ClosestPointResult< maliput::math::Vector3 >
 
using ClosestPointResult2d = ClosestPointResult< maliput::math::Vector2 >
 
using ClosestPointToSegmentResult3d = ClosestPointToSegmentResult< maliput::math::Vector3 >
 
using ClosestPointToSegmentResult2d = ClosestPointToSegmentResult< maliput::math::Vector2 >
 

Functions

LineString3d ComputeCenterline3d (const LineString3d &left, const LineString3d &right)
 Computes a 3-dimensional centerline out of the left and right line string. More...
 
template<typename CoordinateT = maliput::math::Vector3>
CoordinateT InterpolatedPointAtP (const LineString< CoordinateT > &line_string, double p, double tolerance)
 Returns the piecewise linearly interpolated point at the given distance and the distance from the beginning to the first point. More...
 
double GetSlopeAtP (const LineString3d &line_string, double p, double tolerance)
 Returns the slope of a line_string for a given p . More...
 
template<typename CoordinateT = maliput::math::Vector3>
BoundPointsResult GetBoundPointsAtP (const LineString< CoordinateT > &line_string, double p, double tolerance)
 Obtains the points that confines p in the line_string . More...
 
double Get2DHeadingAtP (const LineString3d &line_string, double p, double tolerance)
 Returns the heading of a line_string for a given p . More...
 
maliput::math::Vector2 Get2DTangentAtP (const LineString3d &line_string, double p, double tolerance)
 Returns the 2d-tangent of a line_string for a given p . More...
 
maliput::math::Vector3 GetTangentAtP (const LineString3d &line_string, double p, double tolerance)
 Returns the 3d-tangent of a line_string for a given p . More...
 
template<typename CoordinateT = maliput::math::Vector3>
ClosestPointToSegmentResult< CoordinateT > GetClosestPointToSegment (const CoordinateT &start_segment_point, const CoordinateT &end_segment_point, const CoordinateT &coordinate, double tolerance)
 Gets the closest point in the segment to the given xyz point. More...
 
ClosestPointResult3d GetClosestPoint (const LineString3d &line_string, const maliput::math::Vector3 &xyz, double tolerance)
 Gets the closest point in the line_string to the given xyz point. More...
 
ClosestPointResult3d GetClosestPointUsing2dProjection (const LineString3d &line_string, const maliput::math::Vector3 &xyz, double tolerance)
 Gets the closest point in the line_string to the given xyz point. More...
 
double ComputeDistance (const LineString3d &lhs, const LineString3d &rhs, double tolerance)
 Computes the distance between two LineString3d. More...