hiep sua ten file

This commit is contained in:
2025-12-30 09:57:01 +07:00
parent a183d4bb7b
commit 1fefb2a389
5 changed files with 48 additions and 48 deletions

View File

@@ -37,8 +37,8 @@
#include <robot/duration.h>
#include "laser_geometry/laser_geometry.hpp"
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/LaserScan.h>
#include <robot_sensor_msgs/PointCloud2.h>
#include <robot_sensor_msgs/LaserScan.h>
#define PROJECTION_TEST_RANGE_MIN (0.23f)
#define PROJECTION_TEST_RANGE_MAX (40.0f)
@@ -70,13 +70,13 @@ struct ScanOptions
scan_time_(scan_time) {}
};
sensor_msgs::LaserScan build_constant_scan(const ScanOptions & options)
robot_sensor_msgs::LaserScan build_constant_scan(const ScanOptions & options)
{
if (((options.ang_max_ - options.ang_min_) / options.ang_increment_) < 0) {
throw (BuildScanException());
}
sensor_msgs::LaserScan scan;
robot_sensor_msgs::LaserScan scan;
robot::Time now = robot::Time::now();
scan.header.stamp.sec = now.sec;
scan.header.stamp.nsec = now.nsec;
@@ -100,7 +100,7 @@ sensor_msgs::LaserScan build_constant_scan(const ScanOptions & options)
}
template<typename T>
T cloudData(sensor_msgs::PointCloud2 cloud_out, uint32_t index)
T cloudData(robot_sensor_msgs::PointCloud2 cloud_out, uint32_t index)
{
return *reinterpret_cast<T *>(&cloud_out.data[index]);
}
@@ -157,9 +157,9 @@ TEST(laser_geometry, projectLaser2) {
try {
// printf("%f %f %f %f %f %f\n",
// range, intensity, min_angle, max_angle, angle_increment, scan_time.toSec());
sensor_msgs::LaserScan scan = build_constant_scan(option);
robot_sensor_msgs::LaserScan scan = build_constant_scan(option);
sensor_msgs::PointCloud2 cloud_out;
robot_sensor_msgs::PointCloud2 cloud_out;
projector.projectLaser(scan, cloud_out, -1.0, laser_geometry::channel_option::Index);
EXPECT_EQ(cloud_out.fields.size(), 4u);
projector.projectLaser(scan, cloud_out, -1.0, laser_geometry::channel_option::Intensity);
@@ -205,7 +205,7 @@ TEST(laser_geometry, projectLaser2) {
uint32_t index_offset = 0;
uint32_t distance_offset = 0;
uint32_t stamps_offset = 0;
for (std::vector<sensor_msgs::PointField>::iterator f = cloud_out.fields.begin();
for (std::vector<robot_sensor_msgs::PointField>::iterator f = cloud_out.fields.begin();
f != cloud_out.fields.end(); f++)
{
if (f->name == "x") {x_offset = f->offset;}
@@ -319,11 +319,11 @@ TEST(laser_geometry, transformLaserScanToPointCloud2) {
try {
// printf("%f %f %f %f %f %f\n",
// range, intensity, min_angle, max_angle, angle_increment, scan_time.toSec());
sensor_msgs::LaserScan scan = build_constant_scan(option);
robot_sensor_msgs::LaserScan scan = build_constant_scan(option);
scan.header.frame_id = "laser_frame";
sensor_msgs::PointCloud2 cloud_out;
robot_sensor_msgs::PointCloud2 cloud_out;
projector.transformLaserScanToPointCloud(
scan.header.frame_id, scan, cloud_out, tf3, -1.0,
laser_geometry::channel_option::None);
@@ -377,7 +377,7 @@ TEST(laser_geometry, transformLaserScanToPointCloud2) {
uint32_t index_offset = 0;
uint32_t distance_offset = 0;
uint32_t stamps_offset = 0;
for (std::vector<sensor_msgs::PointField>::iterator f = cloud_out.fields.begin();
for (std::vector<robot_sensor_msgs::PointField>::iterator f = cloud_out.fields.begin();
f != cloud_out.fields.end(); f++)
{
if (f->name == "x") {x_offset = f->offset;}