|
Easy Navigation
|
Classes | |
| class | CircularBuffer |
| Fixed-size circular buffer, thread-safe (mutex-based), copyable. More... | |
| class | ControllerNode |
| ROS 2 lifecycle node that manages calculating speeds for the Easy Navigation system. More... | |
| class | DetectionsPerception |
| class | DetectionsPerceptionsHandler |
| Handles the creation and updating of DetectionsPerceptions instances from sensor_msgs::msg::Image messages. More... | |
| class | DummyController |
| A default "dummy" implementation for the Control Method. More... | |
| class | DummyLocalizer |
| A default "do-nothing" implementation of LocalizerMethodBase. More... | |
| class | DummyMapsManager |
| A default "do-nothing" implementation of MapsManagerBase. More... | |
| class | DummyPlanner |
| A default "do-nothing" implementation of PlannerMethodBase. More... | |
| class | GNSSPerception |
| Represents a single GNSS perception from a sensor. More... | |
| class | GNSSPerceptionHandler |
| Handles the creation and updating of GNSSPerception instances from sensor_msgs::msg::NavSatFix messages. More... | |
| class | GoalManager |
| Handles navigation goals, their lifecycle, and command interface. More... | |
| class | GoalManagerClient |
| Client-side interface for interacting with GoalManager. More... | |
| class | ImagePerception |
| Represents a single image perception from a sensor. More... | |
| class | ImagePerceptionHandler |
| Handles the creation and updating of ImagePerception instances from sensor_msgs::msg::Image messages. More... | |
| class | IMUPerception |
| Represents a single IMU perception from a sensor. More... | |
| class | IMUPerceptionHandler |
| Handles the creation and updating of IMUPerception instances from sensor_msgs::msg::Imu messages. More... | |
| class | LocalizerNode |
| ROS 2 lifecycle node that manages localization in Easy Navigation. More... | |
| class | MapsManagerNode |
| ROS 2 lifecycle node that manages map-related plugins in Easy Navigation. More... | |
| class | NavState |
| A generic, type-safe, thread-safe blackboard to hold runtime state. More... | |
| class | PerceptionBase |
| Abstract base class for representing a single sensor perception. More... | |
| class | PerceptionHandler |
| Abstract base interface for group-specific perception handlers. More... | |
| struct | PerceptionPtr |
| Represents a perception entry with its state and ROS subscription. More... | |
| class | PlannerNode |
| ROS 2 lifecycle node that manages path planning in Easy Navigation. More... | |
| class | PointPerception |
| Concrete perception class for 3D point cloud data. More... | |
| struct | PointPerceptionBufferType |
| class | PointPerceptionHandler |
| PerceptionHandler implementation for sensors producing point-based data. More... | |
| class | PointPerceptionsOpsView |
| Provides efficient, non-destructive, chainable operations over a set of point-based perceptions. More... | |
| class | RTTFBuffer |
| Provides functionality for RTTFBuffer. More... | |
| class | SensorsNode |
| ROS 2 lifecycle node that manages sensor fusion in Easy Navigation. More... | |
| class | Singleton |
| class | SystemNode |
| ROS 2 lifecycle node coordinating all Easy Navigation components. More... | |
| struct | SystemNodeInfo |
| Structure holding runtime information for a subnode. More... | |
| struct | TFInfo |
| Aggregated TF configuration used across EasyNav. More... | |
| class | YTSession |
| A Yaets Tracing Session. More... | |
Typedefs | |
| using | CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn |
| using | DetectionsPerceptions |
| using | GNSSPerceptions |
| Alias for a vector of shared pointers to GNSSPerception objects. | |
| using | ImagePerceptions |
| Alias for a vector of shared pointers to ImagePerception objects. | |
| using | IMUPerceptions |
| Alias for a vector of shared pointers to IMUPerception objects. | |
| using | PerceptionBasePtr = std::shared_ptr<PerceptionBase> |
| Shared pointer alias to PerceptionBase. | |
| using | PointPerceptions |
| Alias for a vector of shared pointers to PointPerception objects. | |
Functions | |
| std::string | backtrace_to_string (std::size_t max_frames=64, std::size_t skip=0) |
| double | calculate_angle (const geometry_msgs::msg::Pose &pose1, const geometry_msgs::msg::Pose &pose2) |
| Get the (absolute) yaw angle difference between two poses. | |
| double | calculate_distance_xy (const geometry_msgs::msg::Pose &pose1, const geometry_msgs::msg::Pose &pose2) |
| Internal utility functions. | |
| void | convert (const sensor_msgs::msg::LaserScan &scan, pcl::PointCloud< pcl::PointXYZ > &pc) |
Converts a LaserScan message into a point cloud. | |
| std::string | demangle (const char *name) |
| Demangles a C++ RTTI type name if possible. | |
| rclcpp::Time | get_latest_detections_perceptions_stamp (const DetectionsPerceptions &perceptions) |
| Retrieves the latest timestamp among a set of detection-based perceptions. | |
| rclcpp::Time | get_latest_gnss_perceptions_stamp (const GNSSPerceptions &perceptions) |
| Retrieves the latest timestamp among a set of GNSS perceptions. | |
| rclcpp::Time | get_latest_image_perceptions_stamp (const ImagePerceptions &perceptions) |
| Retrieves the latest timestamp among a set of image-based perceptions. | |
| rclcpp::Time | get_latest_imu_perceptions_stamp (const IMUPerceptions &perceptions) |
| Retrieves the latest timestamp among a set of IMU perceptions. | |
| rclcpp::Time | get_latest_point_perceptions_stamp (const PointPerceptions &perceptions) |
| Retrieves the latest timestamp among a set of point-based perceptions. | |
| template<typename T = PerceptionBase> | |
| std::vector< std::shared_ptr< T > > | get_perceptions (const std::vector< PerceptionPtr > &src) |
Extracts a homogeneous collection of perceptions of type T from a heterogeneous vector. | |
| PointPerceptions | get_point_perceptions (std::vector< PerceptionPtr > &perceptionptr) |
| Extracts all PointPerception objects from a heterogeneous collection. | |
| constexpr double | norm_angle (const double angle) |
| Angle normalization to [-pi, pi) range (in radians) | |
| sensor_msgs::msg::PointCloud2 | perception_to_rosmsg (const PointPerception &perception) |
Converts a PointPerception into a sensor_msgs::msg::PointCloud2 message. | |
| sensor_msgs::msg::PointCloud2 | points_to_rosmsg (const pcl::PointCloud< pcl::PointXYZ > &points) |
Converts a PCL point cloud into a sensor_msgs::msg::PointCloud2 message. | |
| std::string | stacktrace (std::size_t skip=1, std::size_t max_frames=64) |
| Captures a C/C++ stack trace as a string. | |
Variables | |
| template<class C> | |
| std::once_flag | Singleton< C >::init_flag_ |
| template<class C> | |
| std::unique_ptr< C > | Singleton< C >::instance_ = nullptr |
| using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn |
| using DetectionsPerceptions |
| using GNSSPerceptions |
Alias for a vector of shared pointers to GNSSPerception objects.
The container can represent a time-ordered or batched collection, depending on producer logic.
| using ImagePerceptions |
Alias for a vector of shared pointers to ImagePerception objects.
The container can represent a time-ordered or batched collection, depending on producer logic.
| using IMUPerceptions |
Alias for a vector of shared pointers to IMUPerception objects.
The container can represent a time-ordered or batched collection, depending on producer logic.
| using PerceptionBasePtr = std::shared_ptr<PerceptionBase> |
Shared pointer alias to PerceptionBase.
| using PointPerceptions |
Alias for a vector of shared pointers to PointPerception objects.
| std::string backtrace_to_string | ( | std::size_t | max_frames = 64, |
| std::size_t | skip = 0 ) |
| double calculate_angle | ( | const geometry_msgs::msg::Pose & | pose1, |
| const geometry_msgs::msg::Pose & | pose2 ) |
Get the (absolute) yaw angle difference between two poses.
| pose1 | First pose |
| pose2 | Second pose |
| double calculate_distance_xy | ( | const geometry_msgs::msg::Pose & | pose1, |
| const geometry_msgs::msg::Pose & | pose2 ) |
Internal utility functions.
Get the x/y distance between two poses
| pose1 | First pose |
| pose2 | Second pose |
| void convert | ( | const sensor_msgs::msg::LaserScan & | scan, |
| pcl::PointCloud< pcl::PointXYZ > & | pc ) |
Converts a LaserScan message into a point cloud.
| scan | Input laser scan message. |
| pc | Output point cloud (XYZ). |
| std::string demangle | ( | const char * | name | ) |
Demangles a C++ RTTI type name if possible.
| name | Mangled type name (from typeid(T).name()). |
name. | rclcpp::Time get_latest_detections_perceptions_stamp | ( | const DetectionsPerceptions & | perceptions | ) |
Retrieves the latest timestamp among a set of detection-based perceptions.
| perceptions | Container of detection-based perceptions. |
perceptions, or a default-constructed rclcpp::Time if perceptions is empty. | rclcpp::Time get_latest_gnss_perceptions_stamp | ( | const GNSSPerceptions & | perceptions | ) |
Retrieves the latest timestamp among a set of GNSS perceptions.
| perceptions | Container of GNSS perceptions. |
perceptions, or a default-constructed rclcpp::Time if perceptions is empty. | rclcpp::Time get_latest_image_perceptions_stamp | ( | const ImagePerceptions & | perceptions | ) |
Retrieves the latest timestamp among a set of image-based perceptions.
| perceptions | Container of image-based perceptions. |
perceptions, or a default-constructed rclcpp::Time if perceptions is empty. | rclcpp::Time get_latest_imu_perceptions_stamp | ( | const IMUPerceptions & | perceptions | ) |
Retrieves the latest timestamp among a set of IMU perceptions.
| perceptions | Container of IMU perceptions. |
perceptions, or a default-constructed rclcpp::Time if perceptions is empty. | rclcpp::Time get_latest_point_perceptions_stamp | ( | const PointPerceptions & | perceptions | ) |
Retrieves the latest timestamp among a set of point-based perceptions.
| perceptions | Container of point-based perceptions. |
perceptions, or a default-constructed rclcpp::Time if perceptions is empty. | std::vector< std::shared_ptr< T > > get_perceptions | ( | const std::vector< PerceptionPtr > & | src | ) |
Extracts a homogeneous collection of perceptions of type T from a heterogeneous vector.
This helper iterates the input vector of PerceptionPtr and:
T is exactly PerceptionBase, returns all stored pointers without casting (heterogeneous view).std::dynamic_pointer_cast<T> and includes only those perceptions that match (homogeneous view).| T | Target perception type. Must inherit from PerceptionBase. Defaults to PerceptionBase. |
| src | Source vector containing heterogeneous perceptions and their subscriptions. |
std::shared_ptr<T> containing the matching perceptions, in the same order as src. | PointPerceptions get_point_perceptions | ( | std::vector< PerceptionPtr > & | perceptionptr | ) |
Extracts all PointPerception objects from a heterogeneous collection.
| perceptionptr | Vector of PerceptionPtr entries possibly holding mixed perception types. |
|
constexpr |
Angle normalization to [-pi, pi) range (in radians)
| sensor_msgs::msg::PointCloud2 perception_to_rosmsg | ( | const PointPerception & | perception | ) |
Converts a PointPerception into a sensor_msgs::msg::PointCloud2 message.
| perception | Perception to convert. |
PointCloud2 message. | sensor_msgs::msg::PointCloud2 points_to_rosmsg | ( | const pcl::PointCloud< pcl::PointXYZ > & | points | ) |
Converts a PCL point cloud into a sensor_msgs::msg::PointCloud2 message.
| points | Input point cloud. |
PointCloud2 message. | std::string stacktrace | ( | std::size_t | skip = 1, |
| std::size_t | max_frames = 64 ) |
Captures a C/C++ stack trace as a string.
| skip | Number of initial frames to skip (e.g., the stacktrace frame itself). |
| max_frames | Maximum number of frames to capture. |
| std::once_flag Singleton< C >::init_flag_ |
| std::unique_ptr<C> Singleton< C >::instance_ = nullptr |