Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix connection comments #394

Merged
merged 4 commits into from
May 17, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 7 additions & 5 deletions core/dronecore.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,15 @@ class System;
class DroneCore
{
public:
/** @brief Default UDP bind IP (accepts any incoming connections). */
static constexpr auto DEFAULT_UDP_BIND_IP = "0.0.0.0";
/** @brief Default UDP bind port (same port as used by MAVROS). */
static constexpr int DEFAULT_UDP_PORT = 14540;
/** @brief Default TCP remote IP (localhost). */
static constexpr auto DEFAULT_TCP_REMOTE_IP = "127.0.0.1";
/**< @brief Default TCP remote port. */
static constexpr int DEFAULT_TCP_REMOTE_PORT = 5760;
/**< @brief Default serial baudrate. */
static constexpr int DEFAULT_SERIAL_BAUDRATE = 57600;

/**
Expand All @@ -50,9 +55,6 @@ class DroneCore
* - TCP - tcp://[Remote_host][:Remote_port]
* - Serial - serial://Dev_Node[:Baudrate]
*
* Default URL : udp://0.0.0.0:14540.
* - Default Bind host IP is any local interface (0.0.0.0)
*
* @param connection_url connection URL string.
* @return The result of adding the connection.
*/
Expand Down Expand Up @@ -92,11 +94,11 @@ class DroneCore
/**
* @brief Adds a TCP connection with a specific IP address and port number.
*
* @param remote_ip Remote IP address to connect to (defaults to 127.0.0.1).
* @param remote_ip Remote IP address to connect to.
* @param remote_port The TCP port to connect to (defaults to 5760).
* @return The result of adding the connection.
*/
ConnectionResult add_tcp_connection(const std::string &remote_ip = DEFAULT_TCP_REMOTE_IP,
ConnectionResult add_tcp_connection(const std::string &remote_ip,
int remote_port = DEFAULT_TCP_REMOTE_PORT);

/**
Expand Down
10 changes: 1 addition & 9 deletions core/serial_connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,15 +53,7 @@ namespace dronecore {
SerialConnection::SerialConnection(DroneCoreImpl &parent, const std::string &path, int baudrate):
Connection(parent),
_serial_node(path),
_baudrate(baudrate)
{
if (baudrate == 0) {
_baudrate = DEFAULT_SERIAL_BAUDRATE;
}
if (path == "") {
_serial_node = DEFAULT_SERIAL_DEV_PATH;
}
}
_baudrate(baudrate) {}

SerialConnection::~SerialConnection()
{
Expand Down
6 changes: 2 additions & 4 deletions core/serial_connection.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,8 @@ class SerialConnection : public Connection
void start_recv_thread();
static void receive(SerialConnection *parent);

static constexpr int DEFAULT_SERIAL_BAUDRATE = 9600;
static constexpr auto DEFAULT_SERIAL_DEV_PATH = "/dev/ttyS0";
std::string _serial_node = {};
int _baudrate = DEFAULT_SERIAL_BAUDRATE;
std::string _serial_node;
int _baudrate;

std::mutex _mutex = {};
#if !defined(WINDOWS)
Expand Down