Skip to content

Commit

Permalink
mavconn: Port MAVConnTCPClient to Boost.ASIO.
Browse files Browse the repository at this point in the history
Also it disables MAVConnTCPServer before i rewrite it.
Issue #72.
  • Loading branch information
vooon committed Aug 1, 2014
1 parent 4a9f6a9 commit 31092e7
Show file tree
Hide file tree
Showing 6 changed files with 152 additions and 137 deletions.
33 changes: 19 additions & 14 deletions include/mavros/mavconn_tcp.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,11 @@
#pragma once

#include <list>
#include <ev++.h>
#include <atomic>
#include <boost/asio.hpp>
#include <mavros/mavconn_interface.h>
#include <mavros/mavconn_msgbuffer.h>

#include <arpa/inet.h>
#include <sys/types.h>
#include <sys/socket.h>

namespace mavconn {

/**
Expand All @@ -51,11 +48,13 @@ class MAVConnTCPClient : public MAVConnInterface {
*/
MAVConnTCPClient(uint8_t system_id = 1, uint8_t component_id = MAV_COMP_ID_UDP_BRIDGE,
std::string server_host = "localhost", unsigned short server_port = 5760);
#if 0
/**
* Special client variation for use in MAVConnTCPServer
* @param[in] client_sd socket descriptor
*/
explicit MAVConnTCPClient(uint8_t system_id, uint8_t component_id, int client_sd, sockaddr_in &client_addr);
#endif
~MAVConnTCPClient();

void close();
Expand All @@ -65,24 +64,29 @@ class MAVConnTCPClient : public MAVConnInterface {
void send_bytes(const uint8_t *bytes, size_t length);

inline mavlink_status_t get_status() { return *mavlink_get_channel_status(channel); };
inline bool is_open() { return sockfd != -1; };
inline bool is_open() { return socket.is_open(); };

private:
friend class MAVConnTCPServer;
ev::io io;
int sockfd;
boost::asio::io_service io_service;
std::unique_ptr<boost::asio::io_service::work> io_work;
std::thread io_thread;

sockaddr_in server_addr;
boost::asio::ip::tcp::socket socket;
boost::asio::ip::tcp::endpoint server_ep;

std::atomic<bool> tx_in_progress;
std::list<MsgBuffer*> tx_q;
boost::recursive_mutex mutex;
uint8_t rx_buf[MsgBuffer::MAX_SIZE];
std::recursive_mutex mutex;

void event_cb(ev::io &watcher, int revents);
void read_cb(ev::io &watcher);
void write_cb(ev::io &watcher);
void do_recv();
void async_receive_end(boost::system::error_code, size_t bytes_transferred);
void do_send(bool check_tx_state);
void async_send_end(boost::system::error_code, size_t bytes_transferred);
};


#if 0
/**
* @brief TCP server interface
*
Expand Down Expand Up @@ -122,6 +126,7 @@ class MAVConnTCPServer : public MAVConnInterface {
void client_closed(MAVConnTCPClient *instp);
void recv_message(const mavlink_message_t *message, uint8_t sysid, uint8_t compid);
};
#endif

}; // namespace mavconn

5 changes: 3 additions & 2 deletions src/mavconn/mavconn_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,8 +233,9 @@ static boost::shared_ptr<MAVConnInterface> url_parse_tcp_server(
url_parse_host(host, bind_host, bind_port, "0.0.0.0", 5760);
url_parse_query(query, system_id, component_id);

return boost::make_shared<MAVConnTCPServer>(system_id, component_id,
bind_host, bind_port);
//return boost::make_shared<MAVConnTCPServer>(system_id, component_id,
// bind_host, bind_port);
return boost::shared_ptr<MAVConnInterface>();
}

boost::shared_ptr<MAVConnInterface> MAVConnInterface::open_url(std::string url,
Expand Down
6 changes: 6 additions & 0 deletions src/mavconn/mavconn_serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,12 @@ void MAVConnSerial::close() {
serial_dev.close();
io_service.stop();
/* emit */ port_closed();

// clear tx queue
std::for_each(tx_q.begin(), tx_q.end(),
[](MsgBuffer *p) { delete p; });
tx_q.clear();

io_thread.join();
}

Expand Down
Loading

0 comments on commit 31092e7

Please sign in to comment.