| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /**************************************************************************** | ||
| 2 | * | ||
| 3 | * Copyright (c) 2018 MAVlink Development Team. All rights reserved. | ||
| 4 | * Author: Hannes Diethelm, <hannes.diethelm@gmail.com> | ||
| 5 | * Trent Lukaczyk, <aerialhedgehog@gmail.com> | ||
| 6 | * Jaycee Lock, <jaycee.lock@gmail.com> | ||
| 7 | * Lorenz Meier, <lm@inf.ethz.ch> | ||
| 8 | * | ||
| 9 | * Redistribution and use in source and binary forms, with or without | ||
| 10 | * modification, are permitted provided that the following conditions | ||
| 11 | * are met: | ||
| 12 | * | ||
| 13 | * 1. Redistributions of source code must retain the above copyright | ||
| 14 | * notice, this list of conditions and the following disclaimer. | ||
| 15 | * 2. Redistributions in binary form must reproduce the above copyright | ||
| 16 | * notice, this list of conditions and the following disclaimer in | ||
| 17 | * the documentation and/or other materials provided with the | ||
| 18 | * distribution. | ||
| 19 | * 3. Neither the name PX4 nor the names of its contributors may be | ||
| 20 | * used to endorse or promote products derived from this software | ||
| 21 | * without specific prior written permission. | ||
| 22 | * | ||
| 23 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
| 24 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
| 25 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
| 26 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
| 27 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
| 28 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
| 29 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS | ||
| 30 | * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED | ||
| 31 | * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
| 32 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
| 33 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
| 34 | * POSSIBILITY OF SUCH DAMAGE. | ||
| 35 | * | ||
| 36 | ****************************************************************************/ | ||
| 37 | |||
| 38 | /** | ||
| 39 | * @file udp_port.hpp | ||
| 40 | * | ||
| 41 | * @brief UDP interface definition | ||
| 42 | * | ||
| 43 | * Functions for opening, closing, reading and writing via UDP ports | ||
| 44 | * | ||
| 45 | * @author Hannes Diethelm, <hannes.diethelm@gmail.com> | ||
| 46 | * @author Trent Lukaczyk, <aerialhedgehog@gmail.com> | ||
| 47 | * @author Jaycee Lock, <jaycee.lock@gmail.com> | ||
| 48 | * @author Lorenz Meier, <lm@inf.ethz.ch> | ||
| 49 | * | ||
| 50 | */ | ||
| 51 | |||
| 52 | #pragma once | ||
| 53 | |||
| 54 | #if __linux__ || __APPLE__ | ||
| 55 | // ------------------------------------------------------------------------------ | ||
| 56 | // Includes | ||
| 57 | // ------------------------------------------------------------------------------ | ||
| 58 | |||
| 59 | #include <array> | ||
| 60 | #include <cstdlib> | ||
| 61 | #include <pthread.h> // This uses POSIX Threads | ||
| 62 | #include <sys/socket.h> | ||
| 63 | #include <sys/types.h> | ||
| 64 | #include <netinet/in.h> | ||
| 65 | #include <unistd.h> | ||
| 66 | #include <fcntl.h> | ||
| 67 | #include <sys/time.h> | ||
| 68 | #include <arpa/inet.h> | ||
| 69 | |||
| 70 | #include <mavlink/common/mavlink.h> | ||
| 71 | |||
| 72 | #include "generic_port.hpp" | ||
| 73 | |||
| 74 | // ------------------------------------------------------------------------------ | ||
| 75 | // Defines | ||
| 76 | // ------------------------------------------------------------------------------ | ||
| 77 | |||
| 78 | // ------------------------------------------------------------------------------ | ||
| 79 | // Prototypes | ||
| 80 | // ------------------------------------------------------------------------------ | ||
| 81 | |||
| 82 | // ---------------------------------------------------------------------------------- | ||
| 83 | // UDP Port Manager Class | ||
| 84 | // ---------------------------------------------------------------------------------- | ||
| 85 | /* | ||
| 86 | * UDP Port Class | ||
| 87 | * | ||
| 88 | * This object handles the opening and closing of the offboard computer's | ||
| 89 | * UDP port over which we'll communicate. It also has methods to write | ||
| 90 | * a byte stream buffer. MAVlink is not used in this object yet, it's just | ||
| 91 | * a serialization interface. To help with read and write pthreading, it | ||
| 92 | * gaurds any port operation with a pthread mutex. | ||
| 93 | */ | ||
| 94 | |||
| 95 | /// @brief UDP Port Class | ||
| 96 | class UDP_Port : public Generic_Port | ||
| 97 | { | ||
| 98 | public: | ||
| 99 | /// @brief Default constructor | ||
| 100 | UDP_Port(); | ||
| 101 | /// @brief Constructor | ||
| 102 | UDP_Port(const char* target_ip_, int udp_port_); | ||
| 103 | /// @brief Destructor | ||
| 104 | ~UDP_Port() override; | ||
| 105 | /// @brief Copy constructor | ||
| 106 | UDP_Port(const UDP_Port&) = delete; | ||
| 107 | /// @brief Move constructor | ||
| 108 | UDP_Port(UDP_Port&&) = delete; | ||
| 109 | /// @brief Copy assignment operator | ||
| 110 | UDP_Port& operator=(const UDP_Port&) = delete; | ||
| 111 | /// @brief Move assignment operator | ||
| 112 | UDP_Port& operator=(UDP_Port&&) = delete; | ||
| 113 | |||
| 114 | /// @brief Read message | ||
| 115 | /// @param[in] message Mavlink message to read | ||
| 116 | int read_message(mavlink_message_t& message) override; | ||
| 117 | |||
| 118 | /// @brief Write message | ||
| 119 | /// @param[in] message Mavlink message to write | ||
| 120 | int write_message(const mavlink_message_t& message) override; | ||
| 121 | |||
| 122 | /// @brief Is running | ||
| 123 | ✗ | bool is_running() override | |
| 124 | { | ||
| 125 | ✗ | return is_open; | |
| 126 | } | ||
| 127 | |||
| 128 | /// @brief Start | ||
| 129 | void start() override; | ||
| 130 | |||
| 131 | /// @brief Stop | ||
| 132 | void stop() override; | ||
| 133 | |||
| 134 | private: | ||
| 135 | mavlink_status_t lastStatus{}; ///< Last Mavlink status | ||
| 136 | pthread_mutex_t lock{}; ///< Lock pthread mutex | ||
| 137 | |||
| 138 | /// @brief Initialize defaults | ||
| 139 | void initialize_defaults(); | ||
| 140 | |||
| 141 | const static int BUFF_LEN = 2041; ///< Buffer length | ||
| 142 | std::array<uint8_t, BUFF_LEN> buff{}; ///< Buffer | ||
| 143 | int buff_ptr{}; ///< Pointer to buffer? | ||
| 144 | int buff_len{}; ///< Buffer length | ||
| 145 | bool debug = false; ///< debug flag | ||
| 146 | const char* target_ip = "127.0.0.1"; ///< Target IP address | ||
| 147 | int rx_port{ 14550 }; ///< Receive port | ||
| 148 | int tx_port{ -1 }; ///< Transmit port | ||
| 149 | int sock{ -1 }; ///< Socket | ||
| 150 | bool is_open = false; ///< 'Is open' flag | ||
| 151 | |||
| 152 | /// @brief Read port | ||
| 153 | /// @param[in] cp Port to read | ||
| 154 | int _read_port(uint8_t& cp); | ||
| 155 | |||
| 156 | /// @brief Write port | ||
| 157 | /// @param[in] buf Buffer | ||
| 158 | /// @param[in] len Length of the buffer | ||
| 159 | int _write_port(char* buf, unsigned len); | ||
| 160 | }; | ||
| 161 | |||
| 162 | #endif | ||
| 163 |