Namespaces | Functions
alb_helper.h File Reference
#include "geometry_msgs/PoseStamped.h"
#include "nav_msgs/Odometry.h"
#include "sensor_msgs/PointCloud2.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include <nlohmann/json.hpp>
#include "tlvCommon.h"
#include "outsight_alb_driver/AugmentedCloud.h"
#include "outsight_alb_driver/ObjectData.h"
#include "outsight_alb_driver/Zones.h"
Include dependency graph for alb_helper.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 Helper
 Namespace to define helper functions.
 

Functions

void Helper::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. More...
 
void Helper::define_augmented_cloud (outsight_alb_driver::AugmentedCloud &message, const Tlv::tlv_s *frame)
 Define the AugmentedCloud message. More...
 
void Helper::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. More...
 
void Helper::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. More...
 
void Helper::define_object_speed (outsight_alb_driver::ObjectData &tracked, const Tlv::tlv_s *objectSpeeds, size_t objectIndex)
 Define the tracked object speed. More...
 
void Helper::define_point_fields (sensor_msgs::PointCloud2 &pointCloud)
 Define the point fields for the ALB PointCloud2 message. More...
 
void Helper::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. More...
 
void Helper::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. More...
 
bool Helper::get_egomotion_from_tlv (const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
 Get a ROS egomotion pose from the TLV data. More...
 
std::string Helper::get_object_class (uint32_t classId)
 Get the string class of the tracked object from the ALB. More...
 
bool Helper::get_pose_from_tlv (const Tlv::tlv_s *frame, geometry_msgs::PoseStamped &pose)
 Get a ROS pose from the TLV data. More...
 
void Helper::init_pose (geometry_msgs::Pose &pose)
 Initialize a ROS Pose message. More...
 
void Helper::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. More...
 


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