#include <ros_msgpack_publisher.h>
|
typedef std::map< int, std::map< int, ros_sensor_msgs::LaserScan > > | LaserScanMsgMap |
|
|
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) |
|
std::string | printCoverageTable (const std::map< int, std::map< int, int >> &elevation_azimuth_histograms) |
|
std::string | printElevationAzimuthTable (const std::vector< std::vector< sick_scansegment_xd::PointXYZRAEI32f >> &lidar_points) |
|
void | publishLaserScanMsg (rosNodePtr node, LaserscanMsgPublisher &laserscan_publisher, LaserScanMsgMap &laser_scan_msg_map, int32_t num_echos, int32_t segment_idx) |
|
void | publishPointCloud2Msg (rosNodePtr node, PointCloud2MsgPublisher &publisher, PointCloud2Msg &pointcloud_msg, int32_t num_echos, int32_t segment_idx, int coordinate_notation, const std::string &topic) |
|
Definition at line 158 of file ros_msgpack_publisher.h.
◆ LaserScanMsgMap
◆ RosMsgpackPublisher()
◆ ~RosMsgpackPublisher()
sick_scansegment_xd::RosMsgpackPublisher::~RosMsgpackPublisher |
( |
| ) |
|
|
virtual |
◆ convertPointsToCustomizedFieldsCloud()
◆ convertPointsToLaserscanMsg()
void sick_scansegment_xd::RosMsgpackPublisher::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 |
|
) |
| |
|
protected |
◆ ExportListener()
◆ GetFullframeAngleRanges()
virtual void sick_scansegment_xd::RosMsgpackPublisher::GetFullframeAngleRanges |
( |
float & |
fullframe_azimuth_min_deg, |
|
|
float & |
fullframe_azimuth_max_deg, |
|
|
float & |
fullframe_elevation_min_deg, |
|
|
float & |
fullframe_elevation_max_deg |
|
) |
| const |
|
inlinevirtual |
◆ HandleMsgPackData()
◆ initLFPangleRangeFilterSettings()
bool sick_scansegment_xd::RosMsgpackPublisher::initLFPangleRangeFilterSettings |
( |
const std::string & |
host_LFPangleRangeFilter | ) |
|
|
virtual |
◆ initLFPlayerFilterSettings()
bool sick_scansegment_xd::RosMsgpackPublisher::initLFPlayerFilterSettings |
( |
const std::string & |
host_LFPlayerFilter | ) |
|
|
virtual |
◆ printCoverageTable()
std::string sick_scansegment_xd::RosMsgpackPublisher::printCoverageTable |
( |
const std::map< int, std::map< int, int >> & |
elevation_azimuth_histograms | ) |
|
|
protected |
◆ printElevationAzimuthTable()
Shortcut to publish a PointCloud2Msg Prints (elevation,azimuth) values of all lidar points
Prints (elevation,azimuth) values of all lidar points
Definition at line 425 of file ros_msgpack_publisher.cpp.
◆ publishLaserScanMsg()
◆ publishPointCloud2Msg()
◆ SetActive()
virtual void sick_scansegment_xd::RosMsgpackPublisher::SetActive |
( |
bool |
active | ) |
|
|
inlinevirtual |
◆ m_active
bool sick_scansegment_xd::RosMsgpackPublisher::m_active |
|
protected |
◆ m_all_segments_azimuth_max_deg
float sick_scansegment_xd::RosMsgpackPublisher::m_all_segments_azimuth_max_deg = +180 |
|
protected |
◆ m_all_segments_azimuth_min_deg
float sick_scansegment_xd::RosMsgpackPublisher::m_all_segments_azimuth_min_deg = -180 |
|
protected |
◆ m_all_segments_elevation_max_deg
float sick_scansegment_xd::RosMsgpackPublisher::m_all_segments_elevation_max_deg = 0 |
|
protected |
◆ m_all_segments_elevation_min_deg
float sick_scansegment_xd::RosMsgpackPublisher::m_all_segments_elevation_min_deg = 0 |
|
protected |
◆ m_custom_pointclouds_cfg
◆ m_frame_id
std::string sick_scansegment_xd::RosMsgpackPublisher::m_frame_id |
|
protected |
◆ m_host_FREchoFilter
int sick_scansegment_xd::RosMsgpackPublisher::m_host_FREchoFilter |
|
protected |
◆ m_host_set_FREchoFilter
bool sick_scansegment_xd::RosMsgpackPublisher::m_host_set_FREchoFilter |
|
protected |
◆ m_laserscan_layer_filter
std::vector<int> sick_scansegment_xd::RosMsgpackPublisher::m_laserscan_layer_filter |
|
protected |
◆ m_node
rosNodePtr sick_scansegment_xd::RosMsgpackPublisher::m_node |
|
protected |
◆ m_points_collector
◆ m_publisher_imu
◆ m_publisher_imu_initialized
bool sick_scansegment_xd::RosMsgpackPublisher::m_publisher_imu_initialized = false |
|
protected |
◆ m_publisher_laserscan_360
◆ m_publisher_laserscan_segment
◆ m_scan_time
double sick_scansegment_xd::RosMsgpackPublisher::m_scan_time = 0 |
|
protected |
The documentation for this class was generated from the following files: