Class DataContainerBase

Nested Relationships

Nested Types

Inheritance Relationships

Derived Types

Class Documentation

class DataContainerBase

Subclassed by velodyne_pointcloud::OrganizedCloudXYZIRT, velodyne_pointcloud::PointcloudXYZIRT

Public Functions

inline explicit DataContainerBase(const double min_range, const double max_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int init_width, const unsigned int init_height, const bool is_dense, const unsigned int scans_per_packet, rclcpp::Clock::SharedPtr clock, int fields, ...)
inline virtual ~DataContainerBase()
inline virtual void setup(const velodyne_msgs::msg::VelodyneScan::ConstSharedPtr scan_msg)
virtual void addPoint(float x, float y, float z, const uint16_t ring, const float distance, const float intensity, const float time) = 0
virtual void newLine() = 0
inline const sensor_msgs::msg::PointCloud2 &finishCloud()
inline void manage_tf_buffer()
inline void configure(const double min_range, const double max_range, const std::string &fixed_frame, const std::string &target_frame)
inline bool calculateTransformMatrix(Eigen::Affine3f &matrix, const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time)
inline bool computeTransformToTarget(const rclcpp::Time &scan_time)
inline bool computeTransformToFixed(const rclcpp::Time &packet_time)

Protected Functions

inline void vectorTfToEigen(tf2::Vector3 &tf_vec, Eigen::Vector3f &eigen_vec)
inline void transformPoint(float &x, float &y, float &z)
inline bool pointInRange(float range)

Protected Attributes

sensor_msgs::msg::PointCloud2 cloud
Config config_
rclcpp::Clock::SharedPtr clock_
std::shared_ptr<tf2_ros::TransformListener> tf_listener_
std::shared_ptr<tf2_ros::Buffer> tf_buffer_
Eigen::Affine3f tf_matrix_to_fixed_
Eigen::Affine3f tf_matrix_to_target_
std::string sensor_frame_
struct Config

Public Functions

inline Config(double min_range, double max_range, const std::string &target_frame, const std::string &fixed_frame, unsigned int init_width, unsigned int init_height, bool is_dense, unsigned int scans_per_packet)

Public Members

double min_range

minimum range to publish

double max_range

maximum range to publish

std::string target_frame

output frame of final point cloud

std::string fixed_frame

world fixed frame for ego motion compenstation

unsigned int init_width
unsigned int init_height
bool is_dense
unsigned int scans_per_packet