Class PFLocalizationNode

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class PFLocalizationNode : public rclcpp::Node

ROS Node.

Public Functions

PFLocalizationNode(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
~PFLocalizationNode()

Public Members

NodeParameters nodeParams_
struct NodeParameters

Public Functions

NodeParameters() = default
~NodeParameters() = default
void loadFrom(const mrpt::containers::yaml &cfg)

Public Members

double rate_hz = 2.0

Execution rate in Hz.

double transform_tolerance = 0.1

projection into the future added to the published tf to extend its validity. /tf will be re-published with half this period to ensure that it is always valid in the /tf tree.

double no_update_tolerance = 1.0

maximum time without updating we keep using filter time instead of Time::now

double no_inputs_tolerance = 2.0

maximum time without any observation before start complaining

std::string odom_frame_id = "odom"
std::string global_frame_id = "map"
std::string topic_map = "/mrpt_map/metric_map"
std::string topic_initialpose = "/initialpose"
std::string topic_odometry = "/odom"
std::string pub_topic_particles = "/particlecloud"
std::string pub_topic_pose = "/pf_pose"
std::string topic_sensors_2d_scan

Comma “,” separated list of topics to subscribe for LaserScan msgs.

std::string topic_sensors_point_clouds

Comma “,” separated list of topics to subscribe for PointCloud2 msgs.

std::string topic_gnss = "/gps"

Topic name to subscribe for GNSS msgs: