Skip to content

Commit

Permalink
lib: console-bridge uses macroses...
Browse files Browse the repository at this point in the history
  • Loading branch information
vooon committed May 11, 2018
1 parent 77b6cd1 commit 602e392
Show file tree
Hide file tree
Showing 6 changed files with 53 additions and 101 deletions.
32 changes: 11 additions & 21 deletions libmavconn/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,6 @@ namespace mavconn {
using mavlink::mavlink_message_t;
using mavlink::mavlink_status_t;

// [[[cog:
// import mavros_cog; mavros_cog.outl_using_console_bridge()
// ]]]
using logDebug = CONSOLE_BRIDGE_logDebug;
using logInform = CONSOLE_BRIDGE_logInform;
using logWarn = CONSOLE_BRIDGE_logWarn;
using logError = CONSOLE_BRIDGE_logError;
using logFatal = CONSOLE_BRIDGE_logFatal;
// [[[end]]] (checksum: 9434570e283a11ebd23634876d896ed5)

// static members
std::once_flag MAVConnInterface::init_flag;
std::unordered_map<mavlink::msgid_t, const mavlink::mavlink_msg_entry_t*> MAVConnInterface::message_entries {};
Expand Down Expand Up @@ -143,7 +133,7 @@ void MAVConnInterface::log_recv(const char *pfx, mavlink_message_t &msg, Framing

const char *proto_version_str = (msg.magic == MAVLINK_STX) ? "v2.0" : "v1.0";

logDebug("%s%zu: recv: %s %4s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
CONSOLE_BRIDGE_logDebug("%s%zu: recv: %s %4s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
pfx, conn_id,
proto_version_str,
framing_str,
Expand All @@ -154,15 +144,15 @@ void MAVConnInterface::log_send(const char *pfx, const mavlink_message_t *msg)
{
const char *proto_version_str = (msg->magic == MAVLINK_STX) ? "v2.0" : "v1.0";

logDebug("%s%zu: send: %s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
CONSOLE_BRIDGE_logDebug("%s%zu: send: %s Message-Id: %u [%u bytes] IDs: %u.%u Seq: %u",
pfx, conn_id,
proto_version_str,
msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq);
}

void MAVConnInterface::log_send_obj(const char *pfx, const mavlink::Message &msg)
{
logDebug("%s%zu: send: %s", pfx, conn_id, msg.to_yaml().c_str());
CONSOLE_BRIDGE_logDebug("%s%zu: send: %s", pfx, conn_id, msg.to_yaml().c_str());
}

void MAVConnInterface::send_message_ignore_drop(const mavlink::mavlink_message_t *msg)
Expand All @@ -171,7 +161,7 @@ void MAVConnInterface::send_message_ignore_drop(const mavlink::mavlink_message_t
send_message(msg);
}
catch (std::length_error &e) {
logError(PFX "%zu: DROPPED Message-Id %u [%u bytes] IDs: %u.%u Seq: %u: %s",
CONSOLE_BRIDGE_logError(PFX "%zu: DROPPED Message-Id %u [%u bytes] IDs: %u.%u Seq: %u: %s",
conn_id,
msg->msgid, msg->len, msg->sysid, msg->compid, msg->seq,
e.what());
Expand All @@ -184,7 +174,7 @@ void MAVConnInterface::send_message_ignore_drop(const mavlink::Message &msg)
send_message(msg);
}
catch (std::length_error &e) {
logError(PFX "%zu: DROPPED Message %s: %s",
CONSOLE_BRIDGE_logError(PFX "%zu: DROPPED Message %s: %s",
conn_id,
msg.get_name().c_str(),
e.what());
Expand Down Expand Up @@ -257,14 +247,14 @@ static void url_parse_query(std::string query, uint8_t &sysid, uint8_t &compid)
auto ids_it = std::search(query.begin(), query.end(),
ids_end.begin(), ids_end.end());
if (ids_it == query.end()) {
logWarn(PFX "URL: unknown query arguments");
CONSOLE_BRIDGE_logWarn(PFX "URL: unknown query arguments");
return;
}

std::advance(ids_it, ids_end.length());
auto comma_it = std::find(ids_it, query.end(), ',');
if (comma_it == query.end()) {
logError(PFX "URL: no comma in ids= query");
CONSOLE_BRIDGE_logError(PFX "URL: no comma in ids= query");
return;
}

Expand All @@ -274,7 +264,7 @@ static void url_parse_query(std::string query, uint8_t &sysid, uint8_t &compid)
sysid = std::stoi(sys);
compid = std::stoi(comp);

logDebug(PFX "URL: found system/component id = [%u, %u]", sysid, compid);
CONSOLE_BRIDGE_logDebug(PFX "URL: found system/component id = [%u, %u]", sysid, compid);
}

static MAVConnInterface::Ptr url_parse_serial(
Expand Down Expand Up @@ -302,7 +292,7 @@ static MAVConnInterface::Ptr url_parse_udp(

auto sep_it = std::find(hosts.begin(), hosts.end(), '@');
if (sep_it == hosts.end()) {
logError(PFX "UDP URL should contain @!");
CONSOLE_BRIDGE_logError(PFX "UDP URL should contain @!");
throw DeviceError("url", "UDP separator not found");
}

Expand Down Expand Up @@ -370,7 +360,7 @@ MAVConnInterface::Ptr MAVConnInterface::open_url(std::string url,
proto_end.begin(), proto_end.end());
if (proto_it == url.end()) {
// looks like file path
logDebug(PFX "URL: %s: looks like file path", url.c_str());
CONSOLE_BRIDGE_logDebug(PFX "URL: %s: looks like file path", url.c_str());
return url_parse_serial(url, "", system_id, component_id, false);
}

Expand All @@ -394,7 +384,7 @@ MAVConnInterface::Ptr MAVConnInterface::open_url(std::string url,
++query_it;
query.assign(query_it, url.end());

logDebug(PFX "URL: %s: proto: %s, host: %s, path: %s, query: %s",
CONSOLE_BRIDGE_logDebug(PFX "URL: %s: proto: %s, host: %s, path: %s, query: %s",
url.c_str(), proto.c_str(), host.c_str(),
path.c_str(), query.c_str());

Expand Down
18 changes: 4 additions & 14 deletions libmavconn/src/mavlink_helpers.cpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -26,34 +26,24 @@
// AUTOMATIC GENERATED FILE!
// from src/mavlink_helpers.cpp.em

// [[[cog:
// import mavros_cog; mavros_cog.outl_using_console_bridge()
// ]]]
using logDebug = CONSOLE_BRIDGE_logDebug;
using logInform = CONSOLE_BRIDGE_logInform;
using logWarn = CONSOLE_BRIDGE_logWarn;
using logError = CONSOLE_BRIDGE_logError;
using logFatal = CONSOLE_BRIDGE_logFatal;
// [[[end]]] (checksum: 9434570e283a11ebd23634876d896ed5)

using mavconn::MAVConnInterface;

void MAVConnInterface::init_msg_entry()
{
logDebug("mavconn: Initialize message_entries map");
CONSOLE_BRIDGE_logDebug("mavconn: Initialize message_entries map");

auto load = [&](const char *dialect, const mavlink::mavlink_msg_entry_t & e) {
auto it = message_entries.find(e.msgid);
if (it != message_entries.end()) {
if (memcmp(&e, it->second, sizeof(e)) != 0) {
logDebug("mavconn: init: message from %s, MSG-ID %d ignored! Table has different entry.", dialect, e.msgid);
CONSOLE_BRIDGE_logDebug("mavconn: init: message from %s, MSG-ID %d ignored! Table has different entry.", dialect, e.msgid);
}
else {
logDebug("mavconn: init: message from %s, MSG-ID %d in table.", dialect, e.msgid);
CONSOLE_BRIDGE_logDebug("mavconn: init: message from %s, MSG-ID %d in table.", dialect, e.msgid);
}
}
else {
logDebug("mavconn: init: add message entry for %s, MSG-ID %d", dialect, e.msgid);
CONSOLE_BRIDGE_logDebug("mavconn: init: add message entry for %s, MSG-ID %d", dialect, e.msgid);
message_entries[e.msgid] = &e;
}
};
Expand Down
21 changes: 6 additions & 15 deletions libmavconn/src/serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,6 @@
#endif

namespace mavconn {
// [[[cog:
// import mavros_cog; mavros_cog.outl_using_console_bridge()
// ]]]
using logDebug = CONSOLE_BRIDGE_logDebug;
using logInform = CONSOLE_BRIDGE_logInform;
using logWarn = CONSOLE_BRIDGE_logWarn;
using logError = CONSOLE_BRIDGE_logError;
using logFatal = CONSOLE_BRIDGE_logFatal;
// [[[end]]] (checksum: 9434570e283a11ebd23634876d896ed5)

using boost::system::error_code;
using boost::asio::io_service;
Expand All @@ -57,7 +48,7 @@ MAVConnSerial::MAVConnSerial(uint8_t system_id, uint8_t component_id,
{
using SPB = boost::asio::serial_port_base;

logInform(PFXd "device: %s @ %d bps", conn_id, device.c_str(), baudrate);
CONSOLE_BRIDGE_logInform(PFXd "device: %s @ %d bps", conn_id, device.c_str(), baudrate);

try {
serial_dev.open(device);
Expand Down Expand Up @@ -156,7 +147,7 @@ void MAVConnSerial::close()
void MAVConnSerial::send_bytes(const uint8_t *bytes, size_t length)
{
if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -176,7 +167,7 @@ void MAVConnSerial::send_message(const mavlink_message_t *message)
assert(message != nullptr);

if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -196,7 +187,7 @@ void MAVConnSerial::send_message(const mavlink_message_t *message)
void MAVConnSerial::send_message(const mavlink::Message &message)
{
if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -220,7 +211,7 @@ void MAVConnSerial::do_read(void)
buffer(rx_buf),
[sthis] (error_code error, size_t bytes_transferred) {
if (error) {
logError(PFXd "receive: %s", sthis->conn_id, error.message().c_str());
CONSOLE_BRIDGE_logError(PFXd "receive: %s", sthis->conn_id, error.message().c_str());
sthis->close();
return;
}
Expand Down Expand Up @@ -248,7 +239,7 @@ void MAVConnSerial::do_write(bool check_tx_state)
assert(bytes_transferred <= buf_ref.len);

if (error) {
logError(PFXd "write: %s", sthis->conn_id, error.message().c_str());
CONSOLE_BRIDGE_logError(PFXd "write: %s", sthis->conn_id, error.message().c_str());
sthis->close();
return;
}
Expand Down
35 changes: 13 additions & 22 deletions libmavconn/src/tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,6 @@
#include <mavconn/tcp.h>

namespace mavconn {
// [[[cog:
// import mavros_cog; mavros_cog.outl_using_console_bridge()
// ]]]
using logDebug = CONSOLE_BRIDGE_logDebug;
using logInform = CONSOLE_BRIDGE_logInform;
using logWarn = CONSOLE_BRIDGE_logWarn;
using logError = CONSOLE_BRIDGE_logError;
using logFatal = CONSOLE_BRIDGE_logFatal;
// [[[end]]] (checksum: 9434570e283a11ebd23634876d896ed5)

using boost::system::error_code;
using boost::asio::io_service;
Expand All @@ -56,7 +47,7 @@ static bool resolve_address_tcp(io_service &io, size_t chan, std::string host, u
ep = q_ep;
ep.port(port);
result = true;
logDebug(PFXd "host %s resolved as %s", chan, host.c_str(), to_string_ss(ep).c_str());
CONSOLE_BRIDGE_logDebug(PFXd "host %s resolved as %s", chan, host.c_str(), to_string_ss(ep).c_str());
};

#if BOOST_ASIO_VERSION >= 101200
Expand All @@ -66,7 +57,7 @@ static bool resolve_address_tcp(io_service &io, size_t chan, std::string host, u
#endif

if (ec) {
logWarn(PFXd "resolve error: %s", chan, ec.message().c_str());
CONSOLE_BRIDGE_logWarn(PFXd "resolve error: %s", chan, ec.message().c_str());
result = false;
}

Expand All @@ -89,7 +80,7 @@ MAVConnTCPClient::MAVConnTCPClient(uint8_t system_id, uint8_t component_id,
if (!resolve_address_tcp(io_service, conn_id, server_host, server_port, server_ep))
throw DeviceError("tcp: resolve", "Bind address resolve failed");

logInform(PFXd "Server address: %s", conn_id, to_string_ss(server_ep).c_str());
CONSOLE_BRIDGE_logInform(PFXd "Server address: %s", conn_id, to_string_ss(server_ep).c_str());

try {
socket.open(tcp::v4());
Expand Down Expand Up @@ -124,7 +115,7 @@ MAVConnTCPClient::MAVConnTCPClient(uint8_t system_id, uint8_t component_id,

void MAVConnTCPClient::client_connected(size_t server_channel)
{
logInform(PFXd "Got client, id: %zu, address: %s",
CONSOLE_BRIDGE_logInform(PFXd "Got client, id: %zu, address: %s",
server_channel, conn_id, to_string_ss(server_ep).c_str());

// start recv
Expand Down Expand Up @@ -161,7 +152,7 @@ void MAVConnTCPClient::close()
void MAVConnTCPClient::send_bytes(const uint8_t *bytes, size_t length)
{
if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -181,7 +172,7 @@ void MAVConnTCPClient::send_message(const mavlink_message_t *message)
assert(message != nullptr);

if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -201,7 +192,7 @@ void MAVConnTCPClient::send_message(const mavlink_message_t *message)
void MAVConnTCPClient::send_message(const mavlink::Message &message)
{
if (!is_open()) {
logError(PFXd "send: channel closed!", conn_id);
CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", conn_id);
return;
}

Expand All @@ -225,7 +216,7 @@ void MAVConnTCPClient::do_recv()
buffer(rx_buf),
[sthis] (error_code error, size_t bytes_transferred) {
if (error) {
logError(PFXd "receive: %s", sthis->conn_id, error.message().c_str());
CONSOLE_BRIDGE_logError(PFXd "receive: %s", sthis->conn_id, error.message().c_str());
sthis->close();
return;
}
Expand Down Expand Up @@ -253,7 +244,7 @@ void MAVConnTCPClient::do_send(bool check_tx_state)
assert(bytes_transferred <= buf_ref.len);

if (error) {
logError(PFXd "send: %s", sthis->conn_id, error.message().c_str());
CONSOLE_BRIDGE_logError(PFXd "send: %s", sthis->conn_id, error.message().c_str());
sthis->close();
return;
}
Expand Down Expand Up @@ -290,7 +281,7 @@ MAVConnTCPServer::MAVConnTCPServer(uint8_t system_id, uint8_t component_id,
if (!resolve_address_tcp(io_service, conn_id, server_host, server_port, bind_ep))
throw DeviceError("tcp-l: resolve", "Bind address resolve failed");

logInform(PFXd "Bind address: %s", conn_id, to_string_ss(bind_ep).c_str());
CONSOLE_BRIDGE_logInform(PFXd "Bind address: %s", conn_id, to_string_ss(bind_ep).c_str());

try {
acceptor.open(tcp::v4());
Expand Down Expand Up @@ -323,7 +314,7 @@ void MAVConnTCPServer::close()
if (!is_open())
return;

logInform(PFXd "Terminating server. "
CONSOLE_BRIDGE_logInform(PFXd "Terminating server. "
"All connections will be closed.", conn_id);

io_service.stop();
Expand Down Expand Up @@ -416,7 +407,7 @@ void MAVConnTCPServer::do_accept()
acceptor_client->server_ep,
[sthis, acceptor_client] (error_code error) {
if (error) {
logError(PFXd "accept: %s", sthis->conn_id, error.message().c_str());
CONSOLE_BRIDGE_logError(PFXd "accept: %s", sthis->conn_id, error.message().c_str());
sthis->close();
return;
}
Expand All @@ -437,7 +428,7 @@ void MAVConnTCPServer::client_closed(std::weak_ptr<MAVConnTCPClient> weak_instp)
{
if (auto instp = weak_instp.lock()) {
bool locked = mutex.try_lock();
logInform(PFXd "Client connection closed, id: %p, address: %s",
CONSOLE_BRIDGE_logInform(PFXd "Client connection closed, id: %p, address: %s",
conn_id, instp.get(), to_string_ss(instp->server_ep).c_str());

client_list.remove(instp);
Expand Down
Loading

0 comments on commit 602e392

Please sign in to comment.