Class Node

Nested Relationships

Nested Types

Class Documentation

class Node

Public Functions

Node(const NodeOptions &node_options, std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder, std::shared_ptr<tf2_ros::Buffer> tf_buffer, rclcpp::Node::SharedPtr node, bool collect_metrics)
~Node()
Node(const Node&) = delete
Node &operator=(const Node&) = delete
void FinishAllTrajectories()
bool FinishTrajectory(int trajectory_id)
void RunFinalOptimization()
void StartTrajectoryWithDefaultTopics(const TrajectoryOptions &options)
std::vector<std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId>> ComputeDefaultSensorIdsForMultipleBags(const std::vector<TrajectoryOptions> &bags_options) const
int AddOfflineTrajectory(const std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId> &expected_sensor_ids, const TrajectoryOptions &options)
void HandleOdometryMessage(int trajectory_id, const std::string &sensor_id, const nav_msgs::msg::Odometry::ConstSharedPtr &msg)
void HandleNavSatFixMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::msg::NavSatFix::ConstSharedPtr &msg)
void HandleLandmarkMessage(int trajectory_id, const std::string &sensor_id, const cartographer_ros_msgs::msg::LandmarkList::ConstSharedPtr &msg)
void HandleImuMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::msg::Imu::ConstSharedPtr &msg)
void HandleLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::msg::LaserScan::ConstSharedPtr &msg)
void HandleMultiEchoLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::msg::MultiEchoLaserScan::ConstSharedPtr &msg)
void HandlePointCloud2Message(int trajectory_id, const std::string &sensor_id, const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg)
void SerializeState(const std::string &filename, const bool include_unfinished_submaps)
void LoadState(const std::string &state_filename, bool load_frozen_state)