Program Listing for File tello.hpp
↰ Return to documentation for file (include/tello/tello.hpp)
// Copyright 2024 Universidad Politécnica de Madrid
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Universidad Politécnica de Madrid nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#ifndef TELLO__TELLO_HPP_
#define TELLO__TELLO_HPP_
#include <memory>
#include <cmath>
#include <iostream>
#include <sstream>
#include <string>
#include <thread>
#include <unordered_map>
#include <utility>
#include <vector>
#include "socket_udp.hpp"
#include "opencv2/core.hpp"
#include "opencv2/highgui.hpp"
#include "opencv2/imgcodecs.hpp"
#define COMMAND_SEND_TIMEOUT 220 // Timeout to send a command (ms)
namespace tello
{
struct coordinates
{
double x = 0;
double y = 0;
double z = 0;
};
struct TelloState
{
double stamp = 0; // Time stamp (s) since connection
double pitch = 0; // Pitch angle (rad)
double roll = 0; // Roll angle (rad)
double yaw = 0; // Yaw angle (rad)
double vgx = 0; // Velocity in x (m/s)
double vgy = 0; // Velocity in y (m/s)
double vgz = 0; // Velocity in z (m/s)
double templ = 0; // Lower temperature (°C)
double temph = 0; // Higher temperature (°C)
double tof = 0; // Time of flight (s)
double h = 0; // Height (m)
double bat = 0; // Battery (%)
double baro = 0; // Barometer (m)
double time = 0; // Time (s)
double agx = 0; // Linear acceleration in x (m/s²) TODO(RPS98): Check units
double agy = 0; // Linear acceleration in y (m/s²) TODO(RPS98): Check units
double agz = 0; // Linear acceleration in z (m/s²) TODO(RPS98): Check units
};
class TelloStateReceiver
{
public:
TelloStateReceiver(
const std::string & state_ip = "0.0.0.0",
const int port_state = 8890);
~TelloStateReceiver();
const TelloState & getTelloState();
const std::string & getTelloStateString();
private:
// UPD sockets
std::unique_ptr<SocketUDP> udp_socket_state_; // UDP socket to receive state
// Tello state
std::string tello_state_raw_; // Raw state received from the tello drone
TelloState tello_state_; // State of the tello drone
// Hash map to store the state of the tello drone
std::unordered_map<std::string, double> state_{
{"pitch", 0.0}, {"roll", 0.0}, {"yaw", 0.0}, {"vgx", 0.0}, {"vgy", 0.0}, {"vgz", 0.0},
{"templ", 0.0}, {"temph", 0.0}, {"tof", 0.0}, {"h", 0.0}, {"bat", 0.0}, {"baro", 0.0},
{"time", 0.0}, {"agx", 0.0}, {"agy", 0.0}, {"agz", 0.0}};
// Connection time stamp
std::chrono::time_point<std::chrono::system_clock> connection_time_;
private:
bool parseState(const std::string & data);
};
class TelloCommandSender
{
public:
TelloCommandSender(
const std::string & tello_ip,
const int port_command = 8890,
const int port_command_client = 8890);
~TelloCommandSender();
const std::string & getSDKVersion();
bool getTime(std::string & response);
bool entrySDKMode();
bool setPort(
const int port_state = 8890,
const int port_camera = 11111);
bool takeoff();
bool land();
bool emergency();
bool positionMotionCommand(const double x, const double y, const double z, const double speed);
bool speedMotionCommand(const double vx, const double vy, const double vz, const double yaw);
bool yawMotion(double yaw);
bool sendCameraCommand(
const bool enable, const int timeout_milis = -1);
private:
// UPD sockets
std::unique_ptr<SocketUDP> udp_socket_command_; // UDP socket to send commands
// Tello info
std::string tello_version_ = ""; // Tello version
bool askSDKVersion(std::string & response);
bool sendControlCommand(
const std::string & command, const int timeout_milis = -1);
bool sendReadCommands(
const std::string & command, std::string & response,
const int timeout_milis = -1);
};
class TelloCameraManager
{
public:
TelloCameraManager(
std::shared_ptr<TelloCommandSender> tello_command_sender,
const std::string & stream_url = "udp://0.0.0.0:11111");
~TelloCameraManager();
bool setVideoStream(
const bool enable, const std::string & stream_url);
const cv::Mat & getFrame();
private:
// Tello command sender
std::shared_ptr<TelloCommandSender> tello_command_sender_; // Tello command sender
// Camera
bool camera_enabled_ = false; // Camera enabled
cv::VideoCapture video_stream_capture_; // Video stream capture
cv::Mat video_stream_frame_; // Video stream frame
};
} // namespace tello
#endif // TELLO__TELLO_HPP_