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 |
Class to publish ROS messages from the ALB.
Definition at line 19 of file alb_publisher.h.
AlbPublisher::AlbPublisher | ( | ros::NodeHandle & | nodeHandle | ) |
Definition at line 30 of file alb_publisher.cpp.
|
private |
Broadcast the ALB fixed frame to sensor frame transform.
Definition at line 446 of file alb_publisher.cpp.
|
private |
Broadcast the ALB map to fixed frame transform.
Definition at line 481 of file alb_publisher.cpp.
|
private |
Build ALB zones when the processing starts.
Definition at line 140 of file alb_publisher.cpp.
|
private |
Initialize the ROS publishers.
Definition at line 40 of file alb_publisher.cpp.
|
private |
Initialize the transform frames.
Definition at line 106 of file alb_publisher.cpp.
void AlbPublisher::publish | ( | const Tlv::tlv_s * | frame | ) |
Publish messages from the ALB frame.
Definition at line 163 of file alb_publisher.cpp.
|
private |
Publish the augmented cloud message.
Definition at line 390 of file alb_publisher.cpp.
|
private |
Publish egomotion message.
Definition at line 357 of file alb_publisher.cpp.
|
private |
Publish odometry message.
Definition at line 373 of file alb_publisher.cpp.
|
private |
Publish pointCloud message.
Definition at line 242 of file alb_publisher.cpp.
|
private |
Publish pose message.
Definition at line 286 of file alb_publisher.cpp.
|
private |
Publish TimeReference message.
Definition at line 217 of file alb_publisher.cpp.
|
private |
Publish tracked objects message.
Definition at line 299 of file alb_publisher.cpp.
|
private |
Publish the zones message.
Definition at line 413 of file alb_publisher.cpp.
|
private |
Update current position as the last position.
Definition at line 420 of file alb_publisher.cpp.
|
private |
Update used time stamp with the ALB time stamp.
Definition at line 438 of file alb_publisher.cpp.
|
private |
Definition at line 88 of file alb_publisher.h.
|
private |
Definition at line 101 of file alb_publisher.h.
|
private |
Definition at line 75 of file alb_publisher.h.
|
private |
Definition at line 104 of file alb_publisher.h.
|
private |
Definition at line 80 of file alb_publisher.h.
|
private |
Definition at line 90 of file alb_publisher.h.
|
private |
Definition at line 99 of file alb_publisher.h.
|
private |
Definition at line 81 of file alb_publisher.h.
|
private |
Definition at line 74 of file alb_publisher.h.
|
private |
Definition at line 84 of file alb_publisher.h.
|
private |
Definition at line 79 of file alb_publisher.h.
|
private |
Definition at line 89 of file alb_publisher.h.
|
private |
Definition at line 77 of file alb_publisher.h.
|
private |
Definition at line 82 of file alb_publisher.h.
|
private |
Definition at line 100 of file alb_publisher.h.
|
private |
Definition at line 96 of file alb_publisher.h.
|
private |
Definition at line 83 of file alb_publisher.h.
|
private |
Definition at line 97 of file alb_publisher.h.
|
private |
Definition at line 87 of file alb_publisher.h.
|
private |
Definition at line 76 of file alb_publisher.h.
|
private |
Definition at line 95 of file alb_publisher.h.
|
private |
Definition at line 98 of file alb_publisher.h.
|
private |
Definition at line 105 of file alb_publisher.h.
|
private |
Definition at line 91 of file alb_publisher.h.
|
private |
Definition at line 106 of file alb_publisher.h.
|
private |
Definition at line 93 of file alb_publisher.h.
|
private |
Definition at line 85 of file alb_publisher.h.
|
private |
Definition at line 102 of file alb_publisher.h.