Go to the documentation of this file.
5 #include "geometry_msgs/PoseStamped.h"
6 #include "nav_msgs/Odometry.h"
7 #include "sensor_msgs/PointCloud2.h"
11 #include <nlohmann/json.hpp>
17 #include "outsight_alb_driver/AugmentedCloud.h"
18 #include "outsight_alb_driver/ObjectData.h"
19 #include "outsight_alb_driver/Zones.h"
28 void define_points_data(sensor_msgs::PointCloud2 &pointCloud,
const uint32_t layers,
const uint32_t points,
29 float *pointData,
bool use_colwise_order);
32 void define_pose(geometry_msgs::Pose &pose,
const std::array<float, 3> &position,
const std::array<float, 9> &rotation);
35 void init_pose(geometry_msgs::Pose &pose);
38 void parse_zone_data(
const std::string &raw_zones, outsight_alb_driver::Zones &zones_msg);
44 bool get_pose_from_tlv(
const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose);
53 void computeOdometry(nav_msgs::Odometry &odom,
const geometry_msgs::Pose ¤t_pose,
54 const geometry_msgs::Pose &last_pose,
const geometry_msgs::Pose &first_pose,
float dt);
60 void define_box_size(outsight_alb_driver::ObjectData &tracked,
const Tlv::tlv_s *bBoxSizes,
size_t objectIndex);
63 void define_box_pose(outsight_alb_driver::ObjectData &tracked,
const Tlv::tlv_s *bBoxPoses,
size_t objectIndex);
66 void define_object_speed(outsight_alb_driver::ObjectData &tracked,
const Tlv::tlv_s *objectSpeeds,
size_t objectIndex);
72 #endif //_ALB_HELPER_H
Namespace to define helper functions.
bool get_egomotion_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
Get a ROS egomotion pose from the TLV data.
void define_augmented_cloud(outsight_alb_driver::AugmentedCloud &message, const Tlv::tlv_s *frame)
Define the AugmentedCloud message.
void define_point_fields(sensor_msgs::PointCloud2 &pointCloud)
Define the point fields for the ALB PointCloud2 message.
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.
void define_object_speed(outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *objectSpeeds, size_t objectIndex)
Define the tracked object speed.
bool get_pose_from_tlv(const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
Get a ROS pose from the TLV 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.
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.
void init_pose(geometry_msgs::Pose &pose)
Initialize a ROS Pose message.
std::string get_object_class(uint32_t classId)
Get the string class of the tracked object from the ALB.
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.
void computeOdometry(nav_msgs::Odometry &odom, const geometry_msgs::Pose ¤t_pose, const geometry_msgs::Pose &last_pose, const geometry_msgs::Pose &first_pose, float dt)
Compute the odometry between the last two poses.
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.