alb_helper.h
Go to the documentation of this file.
1 #ifndef _ALB_HELPER_H
2 #define _ALB_HELPER_H
3 
4 // ROS headers
5 #include "geometry_msgs/PoseStamped.h"
6 #include "nav_msgs/Odometry.h"
7 #include "sensor_msgs/PointCloud2.h"
9 
10 // Json parser
11 #include <nlohmann/json.hpp>
12 
13 // Osef headers
14 #include "tlvCommon.h"
15 
16 // Local headers
17 #include "outsight_alb_driver/AugmentedCloud.h"
18 #include "outsight_alb_driver/ObjectData.h"
19 #include "outsight_alb_driver/Zones.h"
20 
22 namespace Helper
23 {
25 void define_point_fields(sensor_msgs::PointCloud2 &pointCloud);
26 
28 void define_points_data(sensor_msgs::PointCloud2 &pointCloud, const uint32_t layers, const uint32_t points,
29  float *pointData, bool use_colwise_order);
30 
32 void define_pose(geometry_msgs::Pose &pose, const std::array<float, 3> &position, const std::array<float, 9> &rotation);
33 
35 void init_pose(geometry_msgs::Pose &pose);
36 
38 void parse_zone_data(const std::string &raw_zones, outsight_alb_driver::Zones &zones_msg);
39 
44 bool get_pose_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose);
45 
50 bool get_egomotion_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose);
51 
53 void computeOdometry(nav_msgs::Odometry &odom, const geometry_msgs::Pose &current_pose,
54  const geometry_msgs::Pose &last_pose, const geometry_msgs::Pose &first_pose, float dt);
55 
57 std::string get_object_class(uint32_t classId);
58 
60 void define_box_size(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *bBoxSizes, size_t objectIndex);
61 
63 void define_box_pose(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *bBoxPoses, size_t objectIndex);
64 
66 void define_object_speed(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *objectSpeeds, size_t objectIndex);
67 
69 void define_augmented_cloud(outsight_alb_driver::AugmentedCloud &message, const Tlv::tlv_s *frame);
70 }; // namespace Helper
71 
72 #endif //_ALB_HELPER_H
Helper
Namespace to define helper functions.
Definition: alb_helper.h:22
Helper::get_egomotion_from_tlv
bool get_egomotion_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
Get a ROS egomotion pose from the TLV data.
Definition: alb_helper.cpp:195
Helper::define_augmented_cloud
void define_augmented_cloud(outsight_alb_driver::AugmentedCloud &message, const Tlv::tlv_s *frame)
Define the AugmentedCloud message.
Definition: alb_helper.cpp:325
Helper::define_point_fields
void define_point_fields(sensor_msgs::PointCloud2 &pointCloud)
Define the point fields for the ALB PointCloud2 message.
Definition: alb_helper.cpp:27
Helper::define_box_pose
void define_box_pose(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *bBoxPoses, size_t objectIndex)
Define the bounding box pose for the tracked object.
Definition: alb_helper.cpp:309
Helper::define_object_speed
void define_object_speed(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *objectSpeeds, size_t objectIndex)
Define the tracked object speed.
Definition: alb_helper.cpp:316
Helper::get_pose_from_tlv
bool get_pose_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
Get a ROS pose from the TLV data.
Definition: alb_helper.cpp:171
Helper::define_points_data
void define_points_data(sensor_msgs::PointCloud2 &pointCloud, const uint32_t layers, const uint32_t points, float *pointData, bool use_colwise_order)
Define the PointCloud2 point data from raw points coming from the ALB.
Definition: alb_helper.cpp:52
Helper::define_box_size
void define_box_size(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *bBoxSizes, size_t objectIndex)
Define the bounding box size for the tracked object.
Definition: alb_helper.cpp:300
Helper::init_pose
void init_pose(geometry_msgs::Pose &pose)
Initialize a ROS Pose message.
Definition: alb_helper.cpp:135
tf2_geometry_msgs.h
Helper::get_object_class
std::string get_object_class(uint32_t classId)
Get the string class of the tracked object from the ALB.
Definition: alb_helper.cpp:289
Helper::parse_zone_data
void parse_zone_data(const std::string &raw_zones, outsight_alb_driver::Zones &zones_msg)
Parse the zone data in the raw string and set them in the Zones msg.
Definition: alb_helper.cpp:146
Helper::computeOdometry
void computeOdometry(nav_msgs::Odometry &odom, const geometry_msgs::Pose &current_pose, const geometry_msgs::Pose &last_pose, const geometry_msgs::Pose &first_pose, float dt)
Compute the odometry between the last two poses.
Definition: alb_helper.cpp:226
tlvCommon.h
Helper::define_pose
void define_pose(geometry_msgs::Pose &pose, const std::array< float, 3 > &position, const std::array< float, 9 > &rotation)
Define a ROS Pose message from ALB position and rotation.
Definition: alb_helper.cpp:88


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