Class Node¶
- Defined in File node.hpp 
Inheritance Relationships¶
Derived Types¶
- public rko_lio::ros::OfflineNode(Class OfflineNode)
- public rko_lio::ros::OnlineNode(Class OnlineNode)
Class Documentation¶
- 
class Node¶
- Subclassed by rko_lio::ros::OfflineNode, rko_lio::ros::OnlineNode - Public Functions - 
Node() = delete¶
 - 
Node(const std::string &node_name, const rclcpp::NodeOptions &options)¶
 - 
void parse_cli_extrinsics()¶
 - 
bool check_and_set_extrinsics()¶
 - 
void registration_loop()¶
 - 
void publish_map_loop()¶
 - 
void dump_results_to_disk(const std::filesystem::path &results_dir, const std::string &run_name) const¶
 - 
~Node()¶
 - Public Members - 
rclcpp::Node::SharedPtr node¶
 - 
core::TimestampProcessingConfig timestamp_proc_config¶
 - 
std::string imu_topic¶
 - 
std::string imu_frame = ""¶
 - 
std::string lidar_topic¶
 - 
std::string lidar_frame = ""¶
 - 
std::string base_frame¶
 - 
std::string odom_frame = "odom"¶
 - 
std::string odom_topic = "/rko_lio/odometry"¶
 - 
std::string map_topic = "/rko_lio/local_map"¶
 - 
bool dump_results = false¶
 - 
std::string results_dir = "results"¶
 - 
std::string run_name = "rko_lio_run"¶
 - 
bool invert_odom_tf = false¶
 - 
bool publish_lidar_acceleration = false¶
 - 
bool publish_deskewed_scan = false¶
 - 
bool publish_local_map = false¶
 - 
Sophus::SE3d extrinsic_imu2base¶
 - 
Sophus::SE3d extrinsic_lidar2base¶
 - 
bool extrinsics_set = false¶
 - 
std::shared_ptr<tf2_ros::TransformListener> tf_listener¶
 - 
std::shared_ptr<tf2_ros::Buffer> tf_buffer¶
 - 
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster¶
 - 
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_publisher¶
 - 
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr frame_publisher¶
 - 
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr map_publisher¶
 - 
rclcpp::Publisher<geometry_msgs::msg::AccelStamped>::SharedPtr lidar_accel_publisher¶
 - 
std::jthread map_publish_thead¶
 - 
std::mutex local_map_mutex¶
 - 
std::jthread registration_thread¶
 - 
std::mutex buffer_mutex¶
 - 
std::condition_variable sync_condition_variable¶
 - 
std::atomic<bool> atomic_node_running = true¶
 - 
std::atomic<bool> atomic_can_process = false¶
 - 
std::queue<core::ImuControl> imu_buffer¶
 - 
std::queue<core::LidarFrame> lidar_buffer¶
 - 
size_t max_lidar_buffer_size = 50¶
 
- 
Node() = delete¶