Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Public Attributes | List of all members
nav2_costmap_2d::Observation Class Reference

Stores an observation in terms of a point cloud and the origin of the source. More...

#include <nav2_costmap_2d/include/nav2_costmap_2d/observation.hpp>

Collaboration diagram for nav2_costmap_2d::Observation:
Collaboration graph
[legend]

Public Member Functions

 Observation ()
 Creates an empty observation.
 
virtual ~Observation ()
 A destructor.
 
Observationoperator= (const Observation &obs)
 Copy assignment operator. More...
 
 Observation (geometry_msgs::msg::Point &origin, const sensor_msgs::msg::PointCloud2 &cloud, double obstacle_max_range, double obstacle_min_range, double raytrace_max_range, double raytrace_min_range)
 Creates an observation from an origin point and a point cloud. More...
 
 Observation (const Observation &obs)
 Copy constructor. More...
 
 Observation (const sensor_msgs::msg::PointCloud2 &cloud, double obstacle_max_range, double obstacle_min_range)
 Creates an observation from a point cloud. More...
 

Public Attributes

geometry_msgs::msg::Point origin_
 
sensor_msgs::msg::PointCloud2 * cloud_
 
double obstacle_max_range_
 
double obstacle_min_range_
 
double raytrace_max_range_
 
double raytrace_min_range_
 

Detailed Description

Stores an observation in terms of a point cloud and the origin of the source.

Note
Tried to make members and constructor arguments const but the compiler would not accept the default assignment operator for vector insertion!

Definition at line 46 of file observation.hpp.

Constructor & Destructor Documentation

◆ Observation() [1/3]

nav2_costmap_2d::Observation::Observation ( geometry_msgs::msg::Point &  origin,
const sensor_msgs::msg::PointCloud2 &  cloud,
double  obstacle_max_range,
double  obstacle_min_range,
double  raytrace_max_range,
double  raytrace_min_range 
)
inline

Creates an observation from an origin point and a point cloud.

Parameters
originThe origin point of the observation
cloudThe point cloud of the observation
obstacle_max_rangeThe range out to which an observation should be able to insert obstacles
obstacle_min_rangeThe range from which an observation should be able to insert obstacles
raytrace_max_rangeThe range out to which an observation should be able to clear via raytracing
raytrace_min_rangeThe range from which an observation should be able to clear via raytracing

Definition at line 91 of file observation.hpp.

◆ Observation() [2/3]

nav2_costmap_2d::Observation::Observation ( const Observation obs)
inline

Copy constructor.

Parameters
obsThe observation to copy

Definition at line 106 of file observation.hpp.

◆ Observation() [3/3]

nav2_costmap_2d::Observation::Observation ( const sensor_msgs::msg::PointCloud2 &  cloud,
double  obstacle_max_range,
double  obstacle_min_range 
)
inline

Creates an observation from a point cloud.

Parameters
cloudThe point cloud of the observation
obstacle_max_rangeThe range out to which an observation should be able to insert obstacles
obstacle_min_rangeThe range from which an observation should be able to insert obstacles

Definition at line 120 of file observation.hpp.

Member Function Documentation

◆ operator=()

Observation& nav2_costmap_2d::Observation::operator= ( const Observation obs)
inline

Copy assignment operator.

Parameters
obsThe observation to copy

Definition at line 70 of file observation.hpp.


The documentation for this class was generated from the following file: