alb_publisher.h
Go to the documentation of this file.
1 #ifndef _ALB_PUBLISHER_H
2 #define _ALB_PUBLISHER_H
3 
4 // ROS headers
5 #include "geometry_msgs/PoseStamped.h"
6 #include "nav_msgs/Odometry.h"
7 #include "ros/ros.h"
8 
11 
12 // Osef headers
13 #include "tlvParser.h"
14 
15 // Local header
16 #include "outsight_alb_driver/Zones.h"
17 
19 class AlbPublisher {
20  public:
21  AlbPublisher(ros::NodeHandle &nodeHandle);
22 
24  void publish(const Tlv::tlv_s *frame);
25 
26  private:
28  void initPublishers(ros::NodeHandle &nodeHandle);
29 
31  void initTransforms();
32 
34  void buildZones();
35 
37  void publishTimeReference(const Tlv::tlv_s *frame);
38 
40  void publishPointCloud(const Tlv::tlv_s *frame);
41 
43  void publishPose(const Tlv::tlv_s *frame);
44 
46  void publishTrackedObjects(const Tlv::tlv_s *frame);
47 
49  void publishEgomotion(const Tlv::tlv_s *frame);
50 
52  void publishOdometry(const Tlv::tlv_s *frame);
53 
55  void publishAugmentedCloud(const Tlv::tlv_s *frame);
56 
58  void publishZones();
59 
61  void updatePose(const Tlv::tlv_s *frame);
62 
64  void updateTimeStamp(const Tlv::tlv_s *frame);
65 
66  private:
68  void broadcastAlbTransform(const geometry_msgs::Pose &pose);
69 
71  void broadcastMapTransform(const geometry_msgs::Pose &pose);
72 
73  private:
74  std::string fixed_frame_id;
75  std::string base_frame_id;
76  std::string sensor_frame_id;
77  std::string map_frame_id;
78 
79  geometry_msgs::Pose last_pose;
80  geometry_msgs::Pose current_pose;
81  geometry_msgs::Pose first_pose;
82  nav_msgs::Odometry odom_msg;
83  bool pose_found;
84  bool get_first_pose = false;
85  outsight_alb_driver::Zones zones_msg;
86 
92 
94 
103 
107 };
108 
109 #endif // _ALB_PUBLISHER_H
AlbPublisher::publish
void publish(const Tlv::tlv_s *frame)
Publish messages from the ALB frame.
Definition: alb_publisher.cpp:163
AlbPublisher::publishOdometry
void publishOdometry(const Tlv::tlv_s *frame)
Publish odometry message.
Definition: alb_publisher.cpp:373
AlbPublisher::first_pose
geometry_msgs::Pose first_pose
Definition: alb_publisher.h:81
AlbPublisher::pose_publisher
ros::Publisher pose_publisher
Definition: alb_publisher.h:97
AlbPublisher::publishZones
void publishZones()
Publish the zones message.
Definition: alb_publisher.cpp:413
AlbPublisher::publishTimeReference
void publishTimeReference(const Tlv::tlv_s *frame)
Publish TimeReference message.
Definition: alb_publisher.cpp:217
AlbPublisher::initPublishers
void initPublishers(ros::NodeHandle &nodeHandle)
Initialize the ROS publishers.
Definition: alb_publisher.cpp:40
AlbPublisher::current_timestamp
ros::Time current_timestamp
Definition: alb_publisher.h:90
ros::Publisher
AlbPublisher::updatePose
void updatePose(const Tlv::tlv_s *frame)
Update current position as the last position.
Definition: alb_publisher.cpp:420
AlbPublisher::publishAugmentedCloud
void publishAugmentedCloud(const Tlv::tlv_s *frame)
Publish the augmented cloud message.
Definition: alb_publisher.cpp:390
AlbPublisher::updateTimeStamp
void updateTimeStamp(const Tlv::tlv_s *frame)
Update used time stamp with the ALB time stamp.
Definition: alb_publisher.cpp:438
AlbPublisher::base_to_lidar_tf
tf2::Transform base_to_lidar_tf
Definition: alb_publisher.h:104
ros.h
AlbPublisher::publishPointCloud
void publishPointCloud(const Tlv::tlv_s *frame)
Publish pointCloud message.
Definition: alb_publisher.cpp:242
AlbPublisher::current_pose
geometry_msgs::Pose current_pose
Definition: alb_publisher.h:80
tlvParser.h
AlbPublisher::egomotion_publisher
ros::Publisher egomotion_publisher
Definition: alb_publisher.h:99
AlbPublisher::get_first_pose
bool get_first_pose
Definition: alb_publisher.h:84
AlbPublisher::transform_broadcaster
bool transform_broadcaster
Definition: alb_publisher.h:105
AlbPublisher::broadcastMapTransform
void broadcastMapTransform(const geometry_msgs::Pose &pose)
Broadcast the ALB map to fixed frame transform.
Definition: alb_publisher.cpp:481
AlbPublisher::use_alb_time
bool use_alb_time
Definition: alb_publisher.h:91
AlbPublisher::pose_found
bool pose_found
Definition: alb_publisher.h:83
AlbPublisher::point_cloud_publisher
ros::Publisher point_cloud_publisher
Definition: alb_publisher.h:96
AlbPublisher::broadcastAlbTransform
void broadcastAlbTransform(const geometry_msgs::Pose &pose)
Broadcast the ALB fixed frame to sensor frame transform.
Definition: alb_publisher.cpp:446
AlbPublisher::fixed_frame_id
std::string fixed_frame_id
Definition: alb_publisher.h:74
AlbPublisher::odometry_publisher
ros::Publisher odometry_publisher
Definition: alb_publisher.h:100
AlbPublisher::zones_msg
outsight_alb_driver::Zones zones_msg
Definition: alb_publisher.h:85
AlbPublisher::augmented_cloud_publisher
ros::Publisher augmented_cloud_publisher
Definition: alb_publisher.h:101
AlbPublisher::publishTrackedObjects
void publishTrackedObjects(const Tlv::tlv_s *frame)
Publish tracked objects message.
Definition: alb_publisher.cpp:299
tf2::Transform
AlbPublisher::initTransforms
void initTransforms()
Initialize the transform frames.
Definition: alb_publisher.cpp:106
AlbPublisher::time_reference_publisher
ros::Publisher time_reference_publisher
Definition: alb_publisher.h:95
AlbPublisher::ros_time
ros::Time ros_time
Definition: alb_publisher.h:87
AlbPublisher::publishEgomotion
void publishEgomotion(const Tlv::tlv_s *frame)
Publish egomotion message.
Definition: alb_publisher.cpp:357
AlbPublisher::use_colwise_order
bool use_colwise_order
Definition: alb_publisher.h:93
transform_listener.h
AlbPublisher
Class to publish ROS messages from the ALB.
Definition: alb_publisher.h:19
AlbPublisher::last_timestamp
ros::Time last_timestamp
Definition: alb_publisher.h:89
AlbPublisher::AlbPublisher
AlbPublisher(ros::NodeHandle &nodeHandle)
Definition: alb_publisher.cpp:30
AlbPublisher::publishPose
void publishPose(const Tlv::tlv_s *frame)
Publish pose message.
Definition: alb_publisher.cpp:286
ros::Time
AlbPublisher::use_base_frame
bool use_base_frame
Definition: alb_publisher.h:106
AlbPublisher::base_frame_id
std::string base_frame_id
Definition: alb_publisher.h:75
AlbPublisher::sensor_frame_id
std::string sensor_frame_id
Definition: alb_publisher.h:76
AlbPublisher::buildZones
void buildZones()
Build ALB zones when the processing starts.
Definition: alb_publisher.cpp:140
tf2_geometry_msgs.h
AlbPublisher::odom_msg
nav_msgs::Odometry odom_msg
Definition: alb_publisher.h:82
AlbPublisher::zones_publisher
ros::Publisher zones_publisher
Definition: alb_publisher.h:102
AlbPublisher::tracked_objects_publisher
ros::Publisher tracked_objects_publisher
Definition: alb_publisher.h:98
AlbPublisher::last_pose
geometry_msgs::Pose last_pose
Definition: alb_publisher.h:79
AlbPublisher::alb_time
ros::Time alb_time
Definition: alb_publisher.h:88
ros::NodeHandle
AlbPublisher::map_frame_id
std::string map_frame_id
Definition: alb_publisher.h:77


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