Skip to content
This repository was archived by the owner on Oct 8, 2025. It is now read-only.

Commit 29cfc2e

Browse files
committed
Blackboard was integrated
1 parent 5cada6c commit 29cfc2e

11 files changed

Lines changed: 929 additions & 0 deletions

File tree

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
cmake_minimum_required(VERSION 3.20)
2+
project(easynav_pointcloud_common)
3+
4+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5+
add_compile_options(-Wall -Wextra -Wpedantic)
6+
endif()
7+
8+
set(CMAKE_CXX_STANDARD 23)
9+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
10+
set(CMAKE_CXX_EXTENSIONS OFF)
11+
12+
find_package(ament_cmake REQUIRED)
13+
find_package(easynav_common REQUIRED)
14+
# find_package(pluginlib REQUIRED)
15+
16+
17+
add_library(${PROJECT_NAME} SHARED
18+
src/easynav_pointcloud_common/PointCloudData.cpp
19+
)
20+
target_include_directories(${PROJECT_NAME} PUBLIC
21+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
22+
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
23+
)
24+
target_link_libraries(${PROJECT_NAME} PUBLIC
25+
easynav_common::easynav_common
26+
# pluginlib::pluginlib
27+
)
28+
29+
install(
30+
DIRECTORY include/
31+
DESTINATION include/${PROJECT_NAME}
32+
)
33+
34+
install(TARGETS
35+
${PROJECT_NAME}
36+
EXPORT export_${PROJECT_NAME}
37+
ARCHIVE DESTINATION lib
38+
LIBRARY DESTINATION lib
39+
RUNTIME DESTINATION lib/${PROJECT_NAME}
40+
)
41+
42+
if(BUILD_TESTING)
43+
find_package(ament_lint_auto REQUIRED)
44+
set(ament_cmake_copyright_FOUND TRUE)
45+
set(ament_cmake_cpplint_FOUND TRUE)
46+
ament_lint_auto_find_test_dependencies()
47+
48+
find_package(ament_cmake_gtest REQUIRED)
49+
#add_subdirectory(tests)
50+
endif()
51+
52+
ament_export_include_directories("include/${PROJECT_NAME}")
53+
ament_export_libraries(${PROJECT_NAME})
54+
ament_export_targets(export_${PROJECT_NAME})
55+
ament_export_dependencies(
56+
easynav_common
57+
# pluginlib
58+
)
59+
ament_package()
Lines changed: 146 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
1+
// Copyright 2025 Intelligent Robotics Lab
2+
//
3+
// This file is part of the project Easy Navigation (EasyNav in short)
4+
// licensed under the GNU General Public License v3.0.
5+
// See <http://www.gnu.org/licenses/> for details.
6+
//
7+
// Easy Navigation program is free software: you can redistribute it and/or modify
8+
// it under the terms of the GNU General Public License as published by
9+
// the Free Software Foundation, either version 3 of the License, or
10+
// (at your option) any later version.
11+
//
12+
// This program is distributed in the hope that it will be useful,
13+
// but WITHOUT ANY WARRANTY; without even the implied warranty of
14+
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15+
// GNU General Public License for more details.
16+
//
17+
// You should have received a copy of the GNU General Public License
18+
// along with this program. If not, see <http://www.gnu.org/licenses/>.
19+
20+
/// \file
21+
/// \brief Declaration of the PointCloudData type.
22+
23+
#ifndef EASYNAV_POINTCLOUD_MAPS_MANAGER_POINTCLOUDDATA_HPP_
24+
#define EASYNAV_POINTCLOUD_MAPS_MANAGER_POINTCLOUDDATA_HPP_
25+
26+
#include <vector>
27+
#include <stdexcept>
28+
#include <algorithm>
29+
#include <utility>
30+
#include <fstream>
31+
#include <sstream>
32+
33+
#include "sensor_msgs/msg/point_cloud2.hpp"
34+
#include "sensor_msgs/msg/point_field.hpp"
35+
#include <pcl/io/pcd_io.h>
36+
#include <pcl/point_types.h>
37+
#include "pcl_conversions/pcl_conversions.h"
38+
#include "pcl/point_types_conversion.h"
39+
40+
41+
namespace easynav
42+
{
43+
44+
/**
45+
* @class PointCloudData
46+
* @brief Point Cloud representation using basic C++ types.
47+
*/
48+
class PointCloudData
49+
{
50+
public:
51+
/**
52+
* @brief Default constructor.
53+
*/
54+
PointCloudData();
55+
56+
/**
57+
* @brief Initialize the map with characteristics of Point Cloud 2.
58+
*
59+
* @param width_ Number of columns.
60+
* @param height_ Number of rows.
61+
* @param point_step_ Number of elements per point.
62+
* @param row_step_ Number of elements per row.
63+
*/
64+
void initialize(
65+
std::size_t width_, std::size_t height_, std::size_t point_step_,
66+
std::size_t row_step_);
67+
68+
/**
69+
* @brief Returns the width (number of columns) of the map.
70+
*/
71+
size_t width() const {return width_;}
72+
73+
/**
74+
* @brief Returns the height (number of rows) of the map.
75+
*/
76+
size_t height() const {return height_;}
77+
78+
/**
79+
* @brief Load map data from a PointCloudData object.
80+
*
81+
* This function get elements from another PointCloudData object to copy data.
82+
*
83+
* @param other PointCloudData object source of data.
84+
*/
85+
void deep_copy(const PointCloudData & other);
86+
87+
/**
88+
* @brief Load map data from sensor_msgs::msg::PointCloud2 message.
89+
*
90+
* This function read data from a Point Cloud 2 msg to set values
91+
* in PointCloudData objects.
92+
*
93+
* @param cloud_msg The Point Cloud 2 message to load from.
94+
*/
95+
void from_point_cloud(const sensor_msgs::msg::PointCloud2 & cloud_msg);
96+
97+
/**
98+
* @brief Updates a sensor_msgs::msg::PointCloud2 message from the sensors
99+
* values into Easynav.
100+
*
101+
* @param cloud_msg The Point Cloud 2 message to be configured.
102+
* @param cloud Point Cloud with updated values from sensors.
103+
*/
104+
void refresh(
105+
sensor_msgs::msg::PointCloud2 & cloud_msg,
106+
pcl::PointCloud<pcl::PointXYZ> & cloud) const;
107+
108+
/**
109+
* @brief Updates a sensor_msgs::msg::PointCloud2 message from the PointCloudData
110+
* contents.
111+
*
112+
* @param cloud_msg The Point Cloud 2 message to fill or update.
113+
*/
114+
void to_point_cloud(sensor_msgs::msg::PointCloud2 & cloud_msg) const;
115+
116+
/**
117+
* @brief Saves the map to a file.
118+
* @param path Path to the output file.
119+
* @return true if the file was written successfully, false otherwise.
120+
*/
121+
bool save_to_file(const std::string & path) const;
122+
123+
/**
124+
* @brief Loads the map from a file.
125+
* @param path Path to the input file.
126+
* @return true if the file was read successfully and is valid, false otherwise.
127+
*/
128+
bool load_from_file(const std::string & path);
129+
130+
void show(void) const;
131+
132+
private:
133+
std::size_t width_;
134+
std::size_t height_;
135+
std::size_t point_step_;
136+
std::size_t row_step_;
137+
std::vector<sensor_msgs::msg::PointField> fields_;
138+
std::vector<uint8_t> data_;
139+
140+
std::vector<sensor_msgs::msg::PointField> get_fields(void) const;
141+
void get_cloud(pcl::PointCloud<pcl::PointXYZ> & cloud) const;
142+
};
143+
144+
} // namespace easynav
145+
146+
#endif // EASYNAV_POINTCLOUD_MAPS_MANAGER_POINTCLOUDDATA_HPP_
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>easynav_pointcloud_common</name>
5+
<version>0.0.1</version>
6+
<description>Easy Navigation: Point Cloud Common Package.</description>
7+
<maintainer email="juanscelyg@gmail.com">juanscelyg</maintainer>
8+
<maintainer email="e.aguado.glez@gmail.com">esther</maintainer>
9+
<license>GPL-3.0-only</license>
10+
11+
<buildtool_depend>ament_cmake</buildtool_depend>
12+
13+
<depend>easynav_common</depend>
14+
<!-- <depend>pluginlib</depend> -->
15+
<depend>ament_index_cpp</depend>
16+
17+
<test_depend>ament_lint_auto</test_depend>
18+
<test_depend>ament_lint_common</test_depend>
19+
<test_depend>ament_cmake_gtest</test_depend>
20+
21+
<export>
22+
<build_type>ament_cmake</build_type>
23+
</export>
24+
</package>

0 commit comments

Comments
 (0)