diff --git a/src/height/src/height_reader.cpp b/src/height/src/height_reader.cpp index 3ba06530..84662f9f 100644 --- a/src/height/src/height_reader.cpp +++ b/src/height/src/height_reader.cpp @@ -2,6 +2,7 @@ #include #include "rclcpp/rclcpp.hpp" +#include "height/msg/height_data.hpp" #include #include @@ -54,15 +55,30 @@ 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("drone/height", 10); } private: void read_height() { - std::cout << "Distance = " << evo_mini->getDistance() << std::endl; + auto msg = height::msg::HeightData(); + + float min = 10000000; + terabee::DistanceData distance_data = evo_mini->getDistance(); + for (size_t i = 0; i < distance_data.size(); i++) + { + msg.heights[i] = distance_data.distance[i]; + if (distance_data.distance[i] < min) + { + min = distance_data.distance[i]; + } + } + msg.min_height = min; + publisher_->publish(msg); } rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Publisher::SharedPtr publisher_; std::unique_ptr factory; std::unique_ptr evo_mini;