move height and lidar message definitions to drone_services package

This commit is contained in:
Sem van der Hoeven
2023-05-25 11:53:55 +02:00
parent bb9fcd97ab
commit fe3917050e
9 changed files with 20 additions and 28 deletions

View File

@@ -19,12 +19,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(TerabeeApi REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(height REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/HeightData.msg"
)
find_package(drone_services REQUIRED)
add_executable(height_reader src/height_reader.cpp)
target_include_directories(height_reader PUBLIC
@@ -38,7 +33,7 @@ ament_target_dependencies(
height_reader
rclcpp
TerabeeApi
height
drone_services
)
install(TARGETS height_reader

View File

@@ -1,2 +0,0 @@
float32[4] heights
float32 min_height

View File

@@ -7,7 +7,7 @@
#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "height/msg/height_data.hpp"
#include "drone_services/msg/height_data.hpp"
#include <terabee/ITerarangerFactory.hpp>
#include <terabee/ITerarangerEvoMini.hpp>
@@ -48,7 +48,7 @@ public:
RCLCPP_INFO(this->get_logger(), "Succesfully initialized Evo mini!");
timer_ = this->create_wall_timer(500ms, std::bind(&HeightReader::read_height, this));
publisher_ = this->create_publisher<height::msg::HeightData>("drone/height", 10);
publisher_ = this->create_publisher<drone_services::msg::HeightData>("drone/height", 10);
}
private:
@@ -58,7 +58,7 @@ private:
*/
void read_height()
{
auto msg = height::msg::HeightData();
auto msg = drone_services::msg::HeightData();
// high initial minimal value
float min = 255;
@@ -82,7 +82,7 @@ private:
// timer for publishing height readings
rclcpp::TimerBase::SharedPtr timer_;
// publisher for height readings
rclcpp::Publisher<height::msg::HeightData>::SharedPtr publisher_;
rclcpp::Publisher<drone_services::msg::HeightData>::SharedPtr publisher_;
// factory for height sensor
std::unique_ptr<terabee::ITerarangerFactory> factory;