Class RosMsgpackPublisher
Defined in File ros_msgpack_publisher.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public sick_scansegment_xd::MsgPackExportListenerIF
(Class MsgPackExportListenerIF)
Class Documentation
-
class RosMsgpackPublisher : public sick_scansegment_xd::MsgPackExportListenerIF
Public Functions
-
RosMsgpackPublisher(const std::string &node_name = "sick_scansegment_xd", const sick_scansegment_xd::Config &config = sick_scansegment_xd::Config())
-
virtual ~RosMsgpackPublisher()
-
virtual bool initLFPangleRangeFilterSettings(const std::string &host_LFPangleRangeFilter)
-
virtual bool initLFPlayerFilterSettings(const std::string &host_LFPlayerFilter)
-
virtual void HandleMsgPackData(const sick_scansegment_xd::ScanSegmentParserOutput &msgpack_data)
-
virtual sick_scansegment_xd::MsgPackExportListenerIF *ExportListener(void)
-
inline virtual void SetActive(bool active)
-
inline virtual void GetFullframeAngleRanges(float &fullframe_azimuth_min_deg, float &fullframe_azimuth_max_deg, float &fullframe_elevation_min_deg, float &fullframe_elevation_max_deg) const
Protected Types
-
typedef std::map<int, std::map<int, ros_sensor_msgs::LaserScan>> LaserScanMsgMap
Protected Functions
-
void convertPointsToCustomizedFieldsCloud(uint32_t timestamp_sec, uint32_t timestamp_nsec, uint64_t lidar_timestamp_start_microsec, const std::vector<std::vector<sick_scansegment_xd::PointXYZRAEI32f>> &lidar_points, CustomPointCloudConfiguration &pointcloud_cfg, PointCloud2Msg &pointcloud_msg)
-
void convertPointsToLaserscanMsg(uint32_t timestamp_sec, uint32_t timestamp_nsec, const std::vector<std::vector<sick_scansegment_xd::PointXYZRAEI32f>> &lidar_points, size_t total_point_count, LaserScanMsgMap &laser_scan_msg_map, const std::string &frame_id, bool is_fullframe)
-
void publishPointCloud2Msg(rosNodePtr node, PointCloud2MsgPublisher &publisher, PointCloud2Msg &pointcloud_msg, int32_t num_echos, int32_t segment_idx, int coordinate_notation, const std::string &topic)
Shortcut to publish a PointCloud2Msg
-
void publishLaserScanMsg(rosNodePtr node, LaserscanMsgPublisher &laserscan_publisher, LaserScanMsgMap &laser_scan_msg_map, int32_t num_echos, int32_t segment_idx)
Shortcut to publish Laserscan messages
-
std::string printElevationAzimuthTable(const std::vector<std::vector<sick_scansegment_xd::PointXYZRAEI32f>> &lidar_points)
Shortcut to publish a PointCloud2Msg Prints (elevation,azimuth) values of all lidar points
-
std::string printCoverageTable(const std::map<int, std::map<int, int>> &elevation_azimuth_histograms)
Prints (elevation,azimuth) values of the coverage table of collected lidar points
Protected Attributes
-
bool m_active
-
rosNodePtr m_node
-
std::string m_frame_id
-
float m_all_segments_azimuth_min_deg = -180
-
float m_all_segments_azimuth_max_deg = +180
-
float m_all_segments_elevation_min_deg = 0
-
float m_all_segments_elevation_max_deg = 0
-
int m_host_FREchoFilter
-
bool m_host_set_FREchoFilter
-
SegmentPointsCollector m_points_collector
-
LaserscanMsgPublisher m_publisher_laserscan_360
-
LaserscanMsgPublisher m_publisher_laserscan_segment
-
ImuMsgPublisher m_publisher_imu
-
bool m_publisher_imu_initialized = false
-
double m_scan_time = 0
-
std::vector<int> m_laserscan_layer_filter
-
std::vector<CustomPointCloudConfiguration> m_custom_pointclouds_cfg
-
class SegmentPointsCollector
Public Functions
-
inline SegmentPointsCollector(int telegram_idx = 0)
-
inline void appendLidarPoints(const std::vector<std::vector<sick_scansegment_xd::PointXYZRAEI32f>> &points, int32_t segment_idx, int32_t telegram_cnt)
-
inline int32_t lastSegmentIdx()
-
inline bool allSegmentsCovered(float all_segments_azimuth_min_deg, float all_segments_azimuth_max_deg, float all_segments_elevation_min_deg, float all_segments_elevation_max_deg)
-
inline int numEchos(void) const
Public Members
-
uint32_t timestamp_sec
-
uint32_t timestamp_nsec
-
int32_t telegram_cnt
-
float min_azimuth
-
float max_azimuth
-
size_t total_point_count
-
uint64_t lidar_timestamp_start_microsec
-
uint64_t lidar_timestamp_stop_microsec
-
std::vector<std::vector<sick_scansegment_xd::PointXYZRAEI32f>> lidar_points
-
std::vector<int32_t> segment_list
-
std::vector<int32_t> telegram_list
-
std::map<int, std::map<int, int>> segment_coverage
-
inline SegmentPointsCollector(int telegram_idx = 0)
-
RosMsgpackPublisher(const std::string &node_name = "sick_scansegment_xd", const sick_scansegment_xd::Config &config = sick_scansegment_xd::Config())