• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 7965506471

19 Feb 2024 09:51PM CUT coverage: 36.22% (+0.008%) from 36.212%
7965506471

push

github

web-flow
Merge pull request #2223 from mavlink/pr-absl-fix

Fix illegal instruction on RPi 4

10035 of 27706 relevant lines covered (36.22%)

127.69 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

0.0
/src/mavsdk/core/tcp_connection.cpp
1
#include "tcp_connection.h"
2
#include "log.h"
3

4
#ifdef WINDOWS
5
#ifndef MINGW
6
#pragma comment(lib, "Ws2_32.lib") // Without this, Ws2_32.lib is not included in static library.
7
#endif
8
#else
9
#include <netinet/in.h>
10
#include <sys/socket.h>
11
#include <arpa/inet.h>
12
#include <errno.h>
13
#include <netdb.h>
14
#include <unistd.h> // for close()
15
#endif
16

17
#include <cassert>
18
#include <utility>
19

20
#ifndef WINDOWS
21
#define GET_ERROR(_x) strerror(_x)
22
#else
23
#define GET_ERROR(_x) WSAGetLastError()
24
#endif
25

26
namespace mavsdk {
27

28
/* change to remote_ip and remote_port */
29
TcpConnection::TcpConnection(
×
30
    Connection::ReceiverCallback receiver_callback,
31
    std::string remote_ip,
32
    int remote_port,
33
    ForwardingOption forwarding_option) :
×
34
    Connection(std::move(receiver_callback), forwarding_option),
×
35
    _remote_ip(std::move(remote_ip)),
×
36
    _remote_port_number(remote_port),
37
    _should_exit(false)
×
38
{}
×
39

40
TcpConnection::~TcpConnection()
×
41
{
42
    // If no one explicitly called stop before, we should at least do it.
43
    stop();
×
44
}
×
45

46
ConnectionResult TcpConnection::start()
×
47
{
48
    if (!start_mavlink_receiver()) {
×
49
        return ConnectionResult::ConnectionsExhausted;
×
50
    }
51

52
    ConnectionResult ret = setup_port();
×
53
    if (ret != ConnectionResult::Success) {
×
54
        return ret;
×
55
    }
56

57
    start_recv_thread();
×
58

59
    return ConnectionResult::Success;
×
60
}
61

62
ConnectionResult TcpConnection::setup_port()
×
63
{
64
#ifdef WINDOWS
65
    WSADATA wsa;
66
    if (WSAStartup(MAKEWORD(2, 2), &wsa) != 0) {
67
        LogErr() << "Error: Winsock failed, error: %d", WSAGetLastError();
68
        _is_ok = false;
69
        return ConnectionResult::SocketError;
70
    }
71
#endif
72

73
    _socket_fd = socket(AF_INET, SOCK_STREAM, 0);
×
74

75
    if (_socket_fd < 0) {
×
76
        LogErr() << "socket error" << GET_ERROR(errno);
×
77
        _is_ok = false;
×
78
        return ConnectionResult::SocketError;
×
79
    }
80

81
    struct sockaddr_in remote_addr {};
×
82
    remote_addr.sin_family = AF_INET;
×
83
    remote_addr.sin_port = htons(_remote_port_number);
×
84

85
    struct hostent* hp;
86
    hp = gethostbyname(_remote_ip.c_str());
×
87
    if (hp == nullptr) {
×
88
        LogErr() << "Could not get host by name";
×
89
        _is_ok = false;
×
90
        return ConnectionResult::SocketConnectionError;
×
91
    }
92

93
    memcpy(&remote_addr.sin_addr, hp->h_addr, hp->h_length);
×
94

95
    if (connect(_socket_fd, reinterpret_cast<sockaddr*>(&remote_addr), sizeof(struct sockaddr_in)) <
×
96
        0) {
97
        LogErr() << "connect error: " << GET_ERROR(errno);
×
98
        _is_ok = false;
×
99
        return ConnectionResult::SocketConnectionError;
×
100
    }
101

102
    _is_ok = true;
×
103
    return ConnectionResult::Success;
×
104
}
105

106
void TcpConnection::start_recv_thread()
×
107
{
108
    _recv_thread = std::make_unique<std::thread>(&TcpConnection::receive, this);
×
109
}
×
110

111
ConnectionResult TcpConnection::stop()
×
112
{
113
    _should_exit = true;
×
114

115
#ifndef WINDOWS
116
    // This should interrupt a recv/recvfrom call.
117
    shutdown(_socket_fd, SHUT_RDWR);
×
118

119
    // But on Mac, closing is also needed to stop blocking recv/recvfrom.
120
    close(_socket_fd);
×
121
#else
122
    shutdown(_socket_fd, SD_BOTH);
123

124
    closesocket(_socket_fd);
125

126
    WSACleanup();
127
#endif
128

129
    if (_recv_thread) {
×
130
        _recv_thread->join();
×
131
        _recv_thread.reset();
×
132
    }
133

134
    // We need to stop this after stopping the receive thread, otherwise
135
    // it can happen that we interfere with the parsing of a message.
136
    stop_mavlink_receiver();
×
137

138
    return ConnectionResult::Success;
×
139
}
140

141
bool TcpConnection::send_message(const mavlink_message_t& message)
×
142
{
143
    if (!_is_ok) {
×
144
        return false;
×
145
    }
146

147
    if (_remote_ip.empty()) {
×
148
        LogErr() << "Remote IP unknown";
×
149
        return false;
×
150
    }
151

152
    if (_remote_port_number == 0) {
×
153
        LogErr() << "Remote port unknown";
×
154
        return false;
×
155
    }
156

157
    struct sockaddr_in dest_addr {};
×
158
    dest_addr.sin_family = AF_INET;
×
159

160
    inet_pton(AF_INET, _remote_ip.c_str(), &dest_addr.sin_addr.s_addr);
×
161

162
    dest_addr.sin_port = htons(_remote_port_number);
×
163

164
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
×
165
    uint16_t buffer_len = mavlink_msg_to_send_buffer(buffer, &message);
×
166

167
    // TODO: remove this assert again
168
    assert(buffer_len <= MAVLINK_MAX_PACKET_LEN);
×
169

170
#if !defined(MSG_NOSIGNAL)
171
    auto flags = 0;
172
#else
173
    auto flags = MSG_NOSIGNAL;
×
174
#endif
175

176
    const auto send_len = sendto(
×
177
        _socket_fd,
178
        reinterpret_cast<char*>(buffer),
179
        buffer_len,
180
        flags,
181
        reinterpret_cast<const sockaddr*>(&dest_addr),
182
        sizeof(dest_addr));
183

184
    if (send_len != buffer_len) {
×
185
        LogErr() << "sendto failure: " << GET_ERROR(errno);
×
186
        _is_ok = false;
×
187
        return false;
×
188
    }
189
    return true;
×
190
}
191

192
void TcpConnection::receive()
×
193
{
194
    // Enough for MTU 1500 bytes.
195
    char buffer[2048];
×
196

197
    while (!_should_exit) {
×
198
        if (!_is_ok) {
×
199
            LogErr() << "TCP receive error, trying to reconnect...";
×
200
            std::this_thread::sleep_for(std::chrono::seconds(1));
×
201
            setup_port();
×
202
        }
203

204
        const auto recv_len = recv(_socket_fd, buffer, sizeof(buffer), 0);
×
205

206
        if (recv_len == 0) {
×
207
            // This can happen when shutdown is called on the socket,
208
            // therefore we check _should_exit again.
209
            _is_ok = false;
×
210
            continue;
×
211
        }
212

213
        if (recv_len < 0) {
×
214
            // This happens on desctruction when close(_socket_fd) is called,
215
            // therefore be quiet.
216
            // LogErr() << "recvfrom error: " << GET_ERROR(errno);
217
            // Something went wrong, we should try to re-connect in next iteration.
218
            _is_ok = false;
×
219
            continue;
×
220
        }
221

222
        _mavlink_receiver->set_new_datagram(buffer, static_cast<int>(recv_len));
×
223

224
        // Parse all mavlink messages in one data packet. Once exhausted, we'll exit while.
225
        while (_mavlink_receiver->parse_message()) {
×
226
            receive_message(_mavlink_receiver->get_last_message(), this);
×
227
        }
228
    }
229
}
×
230

231
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc