add comments

This commit is contained in:
Sem van der Hoeven
2023-05-05 12:57:48 +02:00
parent 07f0202d51
commit 6a29220bc9
3 changed files with 86 additions and 70 deletions

View File

@@ -1,5 +1,10 @@
/**
* @file height_reader.cpp
* @author Sem van der Hoeven (sem.hoeven@gmail.com)
* @brief Uses the Terabee API to read the Terabee Evo Mini
* height sensor data and publishes it on a /drone/height topic
*/
#include <chrono>
#include <iostream>
#include "rclcpp/rclcpp.hpp"
#include "height/msg/height_data.hpp"
@@ -47,12 +52,18 @@ public:
}
private:
/**
* @brief reads the height value from the Terabee Evo Mini sensor and publishes a
*
*/
void read_height()
{
auto msg = height::msg::HeightData();
// high initial minimal value
float min = 255;
terabee::DistanceData distance_data = evo_mini->getDistance();
// add readings and calculate mimimum value
for (size_t i = 0; i < distance_data.size(); i++)
{
msg.heights[i] = distance_data.distance[i];
@@ -61,16 +72,21 @@ private:
min = distance_data.distance[i];
}
}
// add minimum value and publish message
msg.min_height = min;
publisher_->publish(msg);
RCLCPP_INFO(this->get_logger(), "publishing message with min distance %f", msg.min_height);
}
// timer for publishing height readings
rclcpp::TimerBase::SharedPtr timer_;
// publisher for height readings
rclcpp::Publisher<height::msg::HeightData>::SharedPtr publisher_;
// factory for height sensor
std::unique_ptr<terabee::ITerarangerFactory> factory;
// height sensor object pointer
std::unique_ptr<terabee::ITerarangerEvoMini> evo_mini;
};

View File

@@ -1,3 +1,9 @@
/**
* @file heartbeat.cpp
* @author Sem van der Hoeven (sem.hoeven@gmail.com)
* @brief Heartbeat node that keeps the connection between the flight computer
* and PX4 flight controller alive by sending OffboardControl messages
*/
#include <chrono>
#include "rclcpp/rclcpp.hpp"
@@ -46,7 +52,6 @@ private:
// get timestamp and publish message
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
};

View File

@@ -1,17 +1,14 @@
/*
We need to send attitude setpoints to be able to arm the drone:
https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET
We need attitude setpoints because we don't have a GPS:
https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied-manual-control-lost/31565/9
/**
* @file px4_controller.cpp
* @author Sem van der Hoeven (sem.hoeven@gmail.com)
* @brief Controller node to contol the PX4 using attitude or trajectory setpoints.
* It subscribes to the /drone/set_attitude topic to receive control commands
*/
#include <chrono>
#include <math.h>
#include "rclcpp/rclcpp.hpp"
// #include "attitude_msg_code.hpp"
#include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
#include <px4_msgs/msg/trajectory_setpoint.hpp>
@@ -23,8 +20,6 @@ https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied-
#include <std_srvs/srv/empty.hpp>
// #include <px4_msgs/msg/offboard_control_mode.hpp>
#define D_SPEED(x) -x - 9.81
using namespace std::chrono_literals;