Class OnlineImuRateNode¶
Defined in File online_imu_rate_node.cpp
Inheritance Relationships¶
Base Type¶
public rko_lio::ros::BaseNode(Class BaseNode)
Class Documentation¶
-
class OnlineImuRateNode : public rko_lio::ros::BaseNode¶
Public Functions
-
OnlineImuRateNode(const OnlineImuRateNode&) = delete¶
-
OnlineImuRateNode(OnlineImuRateNode&&) = delete¶
-
OnlineImuRateNode &operator=(const OnlineImuRateNode&) = delete¶
-
OnlineImuRateNode &operator=(OnlineImuRateNode&&) = delete¶
-
inline explicit OnlineImuRateNode(const rclcpp::NodeOptions &options)¶
-
inline rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()¶
Public Members
-
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_at_imu_rate_publisher¶
-
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr imu_sub¶
-
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr lidar_sub¶
-
std::string odom_at_imu_rate_topic = "rko_lio/odom_at_imu_rate"¶
-
bool tf_at_imu_rate = false¶
-
OnlineImuRateNode(const OnlineImuRateNode&) = delete¶