Public Member Functions | Private Member Functions | Private Attributes | List of all members
AlbPublisher Class Reference

Class to publish ROS messages from the ALB. More...

#include <alb_publisher.h>

Public Member Functions

 AlbPublisher (ros::NodeHandle &nodeHandle)
 
void publish (const Tlv::tlv_s *frame)
 Publish messages from the ALB frame. More...
 

Private Member Functions

void broadcastAlbTransform (const geometry_msgs::Pose &pose)
 Broadcast the ALB fixed frame to sensor frame transform. More...
 
void broadcastMapTransform (const geometry_msgs::Pose &pose)
 Broadcast the ALB map to fixed frame transform. More...
 
void buildZones ()
 Build ALB zones when the processing starts. More...
 
void initPublishers (ros::NodeHandle &nodeHandle)
 Initialize the ROS publishers. More...
 
void initTransforms ()
 Initialize the transform frames. More...
 
void publishAugmentedCloud (const Tlv::tlv_s *frame)
 Publish the augmented cloud message. More...
 
void publishEgomotion (const Tlv::tlv_s *frame)
 Publish egomotion message. More...
 
void publishOdometry (const Tlv::tlv_s *frame)
 Publish odometry message. More...
 
void publishPointCloud (const Tlv::tlv_s *frame)
 Publish pointCloud message. More...
 
void publishPose (const Tlv::tlv_s *frame)
 Publish pose message. More...
 
void publishTimeReference (const Tlv::tlv_s *frame)
 Publish TimeReference message. More...
 
void publishTrackedObjects (const Tlv::tlv_s *frame)
 Publish tracked objects message. More...
 
void publishZones ()
 Publish the zones message. More...
 
void updatePose (const Tlv::tlv_s *frame)
 Update current position as the last position. More...
 
void updateTimeStamp (const Tlv::tlv_s *frame)
 Update used time stamp with the ALB time stamp. More...
 

Private Attributes

ros::Time alb_time
 
ros::Publisher augmented_cloud_publisher
 
std::string base_frame_id
 
tf2::Transform base_to_lidar_tf
 
geometry_msgs::Pose current_pose
 
ros::Time current_timestamp
 
ros::Publisher egomotion_publisher
 
geometry_msgs::Pose first_pose
 
std::string fixed_frame_id
 
bool get_first_pose = false
 
geometry_msgs::Pose last_pose
 
ros::Time last_timestamp
 
std::string map_frame_id
 
nav_msgs::Odometry odom_msg
 
ros::Publisher odometry_publisher
 
ros::Publisher point_cloud_publisher
 
bool pose_found
 
ros::Publisher pose_publisher
 
ros::Time ros_time
 
std::string sensor_frame_id
 
ros::Publisher time_reference_publisher
 
ros::Publisher tracked_objects_publisher
 
bool transform_broadcaster
 
bool use_alb_time
 
bool use_base_frame
 
bool use_colwise_order
 
outsight_alb_driver::Zones zones_msg
 
ros::Publisher zones_publisher
 

Detailed Description

Class to publish ROS messages from the ALB.

Definition at line 19 of file alb_publisher.h.

Constructor & Destructor Documentation

◆ AlbPublisher()

AlbPublisher::AlbPublisher ( ros::NodeHandle nodeHandle)

Definition at line 30 of file alb_publisher.cpp.

Member Function Documentation

◆ broadcastAlbTransform()

void AlbPublisher::broadcastAlbTransform ( const geometry_msgs::Pose pose)
private

Broadcast the ALB fixed frame to sensor frame transform.

Definition at line 446 of file alb_publisher.cpp.

◆ broadcastMapTransform()

void AlbPublisher::broadcastMapTransform ( const geometry_msgs::Pose pose)
private

Broadcast the ALB map to fixed frame transform.

Definition at line 481 of file alb_publisher.cpp.

◆ buildZones()

void AlbPublisher::buildZones ( )
private

Build ALB zones when the processing starts.

Definition at line 140 of file alb_publisher.cpp.

◆ initPublishers()

void AlbPublisher::initPublishers ( ros::NodeHandle nodeHandle)
private

Initialize the ROS publishers.

Definition at line 40 of file alb_publisher.cpp.

◆ initTransforms()

void AlbPublisher::initTransforms ( )
private

Initialize the transform frames.

Definition at line 106 of file alb_publisher.cpp.

◆ publish()

void AlbPublisher::publish ( const Tlv::tlv_s *  frame)

Publish messages from the ALB frame.

Definition at line 163 of file alb_publisher.cpp.

◆ publishAugmentedCloud()

void AlbPublisher::publishAugmentedCloud ( const Tlv::tlv_s *  frame)
private

Publish the augmented cloud message.

Definition at line 390 of file alb_publisher.cpp.

◆ publishEgomotion()

void AlbPublisher::publishEgomotion ( const Tlv::tlv_s *  frame)
private

Publish egomotion message.

Definition at line 357 of file alb_publisher.cpp.

◆ publishOdometry()

void AlbPublisher::publishOdometry ( const Tlv::tlv_s *  frame)
private

Publish odometry message.

Definition at line 373 of file alb_publisher.cpp.

◆ publishPointCloud()

void AlbPublisher::publishPointCloud ( const Tlv::tlv_s *  frame)
private

Publish pointCloud message.

Definition at line 242 of file alb_publisher.cpp.

◆ publishPose()

void AlbPublisher::publishPose ( const Tlv::tlv_s *  frame)
private

Publish pose message.

Definition at line 286 of file alb_publisher.cpp.

◆ publishTimeReference()

void AlbPublisher::publishTimeReference ( const Tlv::tlv_s *  frame)
private

Publish TimeReference message.

Definition at line 217 of file alb_publisher.cpp.

◆ publishTrackedObjects()

void AlbPublisher::publishTrackedObjects ( const Tlv::tlv_s *  frame)
private

Publish tracked objects message.

Definition at line 299 of file alb_publisher.cpp.

◆ publishZones()

void AlbPublisher::publishZones ( )
private

Publish the zones message.

Definition at line 413 of file alb_publisher.cpp.

◆ updatePose()

void AlbPublisher::updatePose ( const Tlv::tlv_s *  frame)
private

Update current position as the last position.

Definition at line 420 of file alb_publisher.cpp.

◆ updateTimeStamp()

void AlbPublisher::updateTimeStamp ( const Tlv::tlv_s *  frame)
private

Update used time stamp with the ALB time stamp.

Definition at line 438 of file alb_publisher.cpp.

Member Data Documentation

◆ alb_time

ros::Time AlbPublisher::alb_time
private

Definition at line 88 of file alb_publisher.h.

◆ augmented_cloud_publisher

ros::Publisher AlbPublisher::augmented_cloud_publisher
private

Definition at line 101 of file alb_publisher.h.

◆ base_frame_id

std::string AlbPublisher::base_frame_id
private

Definition at line 75 of file alb_publisher.h.

◆ base_to_lidar_tf

tf2::Transform AlbPublisher::base_to_lidar_tf
private

Definition at line 104 of file alb_publisher.h.

◆ current_pose

geometry_msgs::Pose AlbPublisher::current_pose
private

Definition at line 80 of file alb_publisher.h.

◆ current_timestamp

ros::Time AlbPublisher::current_timestamp
private

Definition at line 90 of file alb_publisher.h.

◆ egomotion_publisher

ros::Publisher AlbPublisher::egomotion_publisher
private

Definition at line 99 of file alb_publisher.h.

◆ first_pose

geometry_msgs::Pose AlbPublisher::first_pose
private

Definition at line 81 of file alb_publisher.h.

◆ fixed_frame_id

std::string AlbPublisher::fixed_frame_id
private

Definition at line 74 of file alb_publisher.h.

◆ get_first_pose

bool AlbPublisher::get_first_pose = false
private

Definition at line 84 of file alb_publisher.h.

◆ last_pose

geometry_msgs::Pose AlbPublisher::last_pose
private

Definition at line 79 of file alb_publisher.h.

◆ last_timestamp

ros::Time AlbPublisher::last_timestamp
private

Definition at line 89 of file alb_publisher.h.

◆ map_frame_id

std::string AlbPublisher::map_frame_id
private

Definition at line 77 of file alb_publisher.h.

◆ odom_msg

nav_msgs::Odometry AlbPublisher::odom_msg
private

Definition at line 82 of file alb_publisher.h.

◆ odometry_publisher

ros::Publisher AlbPublisher::odometry_publisher
private

Definition at line 100 of file alb_publisher.h.

◆ point_cloud_publisher

ros::Publisher AlbPublisher::point_cloud_publisher
private

Definition at line 96 of file alb_publisher.h.

◆ pose_found

bool AlbPublisher::pose_found
private

Definition at line 83 of file alb_publisher.h.

◆ pose_publisher

ros::Publisher AlbPublisher::pose_publisher
private

Definition at line 97 of file alb_publisher.h.

◆ ros_time

ros::Time AlbPublisher::ros_time
private

Definition at line 87 of file alb_publisher.h.

◆ sensor_frame_id

std::string AlbPublisher::sensor_frame_id
private

Definition at line 76 of file alb_publisher.h.

◆ time_reference_publisher

ros::Publisher AlbPublisher::time_reference_publisher
private

Definition at line 95 of file alb_publisher.h.

◆ tracked_objects_publisher

ros::Publisher AlbPublisher::tracked_objects_publisher
private

Definition at line 98 of file alb_publisher.h.

◆ transform_broadcaster

bool AlbPublisher::transform_broadcaster
private

Definition at line 105 of file alb_publisher.h.

◆ use_alb_time

bool AlbPublisher::use_alb_time
private

Definition at line 91 of file alb_publisher.h.

◆ use_base_frame

bool AlbPublisher::use_base_frame
private

Definition at line 106 of file alb_publisher.h.

◆ use_colwise_order

bool AlbPublisher::use_colwise_order
private

Definition at line 93 of file alb_publisher.h.

◆ zones_msg

outsight_alb_driver::Zones AlbPublisher::zones_msg
private

Definition at line 85 of file alb_publisher.h.

◆ zones_publisher

ros::Publisher AlbPublisher::zones_publisher
private

Definition at line 102 of file alb_publisher.h.


The documentation for this class was generated from the following files:


outsight_alb_driver
Author(s): Outsight
autogenerated on Thu Oct 13 2022 02:21:45