diff --git a/drone_sensors/src/height_sensor.cpp b/drone_sensors/src/height_sensor.cpp index a771d0ff..9f1a1386 100644 --- a/drone_sensors/src/height_sensor.cpp +++ b/drone_sensors/src/height_sensor.cpp @@ -1,5 +1,5 @@ #include //time measurement -#include // reading from serial port +#include // reading from serial port #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" @@ -16,6 +16,8 @@ class HeightSensorPublisher : public rclcpp::Node 500ms, std::bind(&HeightSensorPublisher::timer_callback, this)); RCLCPP_INFO(this->get_logger(), "Constructor of height sensor publisher"); + setup_serial_port(); + } private: void timer_callback() @@ -25,8 +27,28 @@ class HeightSensorPublisher : public rclcpp::Node RCLCPP_INFO(this->get_logger(), "Publishing: %s", message.data.c_str()); publisher_->publish(message); } + + /** + * @brief Set the up serial port object to read from the sensor (/dev/ttyACM0) + * + */ + void setup_serial_port() + { + serial_port.open("/dev/ttyACM0", std::ios::in); + if (!serial_port.is_open()) + { + RCLCPP_ERROR(this->get_logger(), "Could not open serial port"); + } + else + { + RCLCPP_INFO(this->get_logger(), "Serial port opened"); + } + + serial_port.close(); + } rclcpp::TimerBase::SharedPtr timer_; rclcpp::Publisher::SharedPtr publisher_; + std::fstream serial_port; // serial port for reading from device }; int main(int argc, char *argv[])