Package Details: ros-indigo-libmavconn 0.17.4-1

Git Clone URL: https://aur.archlinux.org/ros-indigo-libmavconn.git (read-only)
Package Base: ros-indigo-libmavconn
Description: ROS - MAVLink communication library.
Upstream URL: http://wiki.ros.org/mavros
Licenses: GPLv3, LGPLv3, BSD
Submitter: bchretien
Maintainer: None
Last Packager: pryre
Votes: 0
Popularity: 0.000000
First Submitted: 2015-11-02 02:41
Last Updated: 2016-07-22 03:34

Latest Comments

jerry73204 commented on 2018-11-03 13:57

It cannot build with newer boost and cannot build without ros-indigo-console-bridge. Please add these patches in this order.

Patch for boost

diff --git a/src/tcp.cpp b/src/tcp.cpp
index 799b43156..5c9962c80 100644
--- a/src/tcp.cpp
+++ b/src/tcp.cpp
@@ -39,14 +39,19 @@ static bool resolve_address_tcp(io_service &io, int chan, std::string host, unsi
    error_code ec;

    tcp::resolver::query query(host, "");
-   std::for_each(resolver.resolve(query, ec), tcp::resolver::iterator(),
-       [&](const tcp::endpoint &q_ep) {
-           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());
-       });

+   auto fn = [&](const tcp::endpoint & q_ep) {
+       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());
+   };
+
+#if BOOST_ASIO_VERSION >= 101200
+   for (auto q_ep : resolver.resolve(query, ec)) fn(q_ep);
+#else
+   std::for_each(resolver.resolve(query, ec), tcp::resolver::iterator(), fn);
+#endif
    if (ec) {
        logWarn(PFXd "resolve error: %s", chan, ec.message().c_str());
        result = false;
diff --git a/src/udp.cpp b/src/udp.cpp
index 13babc1aa..943ea78d9 100644
--- a/src/udp.cpp
+++ b/src/udp.cpp
@@ -39,13 +39,12 @@ static bool resolve_address_udp(io_service &io, int chan, std::string host, unsi
    error_code ec;

    udp::resolver::query query(host, "");
-   std::for_each(resolver.resolve(query, ec), udp::resolver::iterator(),
-       [&](const udp::endpoint &q_ep) {
-           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());
-       });
+   auto fn = [&](const udp::endpoint & q_ep) {
+       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());
+   };

    if (ec) {
        logWarn(PFXd "resolve error: %s", chan, ec.message().c_str());

Patch for console_bridge

diff --git a/src/interface.cpp b/src/interface.cpp
index de4d77884..124e96c87 100644
--- a/src/interface.cpp
+++ b/src/interface.cpp
@@ -55,19 +55,19 @@ int MAVConnInterface::new_channel() {

    for (chan = 0; chan < MAVLINK_COMM_NUM_BUFFERS; chan++) {
        if (allocated_channels.count(chan) == 0) {
-           logDebug(PFX "Allocate new channel: %d", chan);
+           CONSOLE_BRIDGE_logDebug(PFX "Allocate new channel: %d", chan);
            allocated_channels.insert(chan);
            return chan;
        }
    }

-   logError(PFX "channel overrun");
+   CONSOLE_BRIDGE_logError(PFX "channel overrun");
    return -1;
 }

 void MAVConnInterface::delete_channel(int chan) {
    std::lock_guard<std::recursive_mutex> lock(channel_mutex);
-   logDebug(PFX "Freeing channel: %d", chan);
+   CONSOLE_BRIDGE_logDebug(PFX "Freeing channel: %d", chan);
    allocated_channels.erase(allocated_channels.find(chan));
 }

@@ -193,14 +193,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;
    }

@@ -210,7 +210,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(
@@ -238,7 +238,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");
    }

@@ -303,7 +303,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);
    }

@@ -327,7 +327,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());

diff --git a/src/serial.cpp b/src/serial.cpp
index 655601fdb..f34c1ae6c 100644
--- a/src/serial.cpp
+++ b/src/serial.cpp
@@ -38,7 +38,7 @@ MAVConnSerial::MAVConnSerial(uint8_t system_id, uint8_t component_id,
    io_service(),
    serial_dev(io_service)
 {
-   logInform(PFXd "device: %s @ %d bps", channel, device.c_str(), baudrate);
+   CONSOLE_BRIDGE_logInform(PFXd "device: %s @ %d bps", channel, device.c_str(), baudrate);

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

@@ -106,11 +106,11 @@ void MAVConnSerial::send_message(const mavlink_message_t *message, uint8_t sysid
    assert(message != nullptr);

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

-   logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+   CONSOLE_BRIDGE_logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
            channel, message->msgid, message->len, sysid, compid, message->seq);

    MsgBuffer *buf = new_msgbuffer(message, sysid, compid);
@@ -137,7 +137,7 @@ void MAVConnSerial::async_read_end(error_code error, size_t bytes_transferred)
    mavlink_status_t status;

    if (error) {
-       logError(PFXd "receive: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "receive: %s", channel, error.message().c_str());
        close();
        return;
    }
@@ -145,7 +145,7 @@ void MAVConnSerial::async_read_end(error_code error, size_t bytes_transferred)
    iostat_rx_add(bytes_transferred);
    for (size_t i = 0; i < bytes_transferred; i++) {
        if (mavlink_parse_char(channel, rx_buf[i], &message, &status)) {
-           logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+           CONSOLE_BRIDGE_logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
                    channel, message.msgid, message.len, message.sysid, message.compid, message.seq);

            /* emit */ message_received(&message, message.sysid, message.compid);
@@ -177,7 +177,7 @@ void MAVConnSerial::do_write(bool check_tx_state)
 void MAVConnSerial::async_write_end(error_code error, size_t bytes_transferred)
 {
    if (error) {
-       logError(PFXd "write: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "write: %s", channel, error.message().c_str());
        close();
        return;
    }
diff --git a/src/tcp.cpp b/src/tcp.cpp
index 5c9962c80..a83343c32 100644
--- a/src/tcp.cpp
+++ b/src/tcp.cpp
@@ -44,7 +44,7 @@ static bool resolve_address_tcp(io_service &io, int chan, std::string host, unsi
        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
@@ -53,7 +53,7 @@ static bool resolve_address_tcp(io_service &io, int chan, std::string host, unsi
    std::for_each(resolver.resolve(query, ec), tcp::resolver::iterator(), fn);
 #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;
    }

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

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

    try {
        socket.open(tcp::v4());
@@ -102,7 +102,7 @@ MAVConnTCPClient::MAVConnTCPClient(uint8_t system_id, uint8_t component_id,
 }

 void MAVConnTCPClient::client_connected(int server_channel) {
-   logInform(PFXd "Got client, channel: %d, address: %s",
+   CONSOLE_BRIDGE_logInform(PFXd "Got client, channel: %d, address: %s",
            server_channel, channel, to_string_ss(server_ep).c_str());

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

@@ -153,11 +153,11 @@ void MAVConnTCPClient::send_message(const mavlink_message_t *message, uint8_t sy
    assert(message != nullptr);

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

-   logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+   CONSOLE_BRIDGE_logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
            channel, message->msgid, message->len, sysid, compid, message->seq);

    MsgBuffer *buf = new_msgbuffer(message, sysid, compid);
@@ -184,7 +184,7 @@ void MAVConnTCPClient::async_receive_end(error_code error, size_t bytes_transfer
    mavlink_status_t status;

    if (error) {
-       logError(PFXd "receive: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "receive: %s", channel, error.message().c_str());
        close();
        return;
    }
@@ -192,7 +192,7 @@ void MAVConnTCPClient::async_receive_end(error_code error, size_t bytes_transfer
    iostat_rx_add(bytes_transferred);
    for (size_t i = 0; i < bytes_transferred; i++) {
        if (mavlink_parse_char(channel, rx_buf[i], &message, &status)) {
-           logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+           CONSOLE_BRIDGE_logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
                    channel, message.msgid, message.len, message.sysid, message.compid, message.seq);

            /* emit */ message_received(&message, message.sysid, message.compid);
@@ -224,7 +224,7 @@ void MAVConnTCPClient::do_send(bool check_tx_state)
 void MAVConnTCPClient::async_send_end(error_code error, size_t bytes_transferred)
 {
    if (error) {
-       logError(PFXd "send: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "send: %s", channel, error.message().c_str());
        close();
        return;
    }
@@ -261,7 +261,7 @@ MAVConnTCPServer::MAVConnTCPServer(uint8_t system_id, uint8_t component_id,
    if (!resolve_address_tcp(io_service, channel, server_host, server_port, bind_ep))
        throw DeviceError("tcp-l: resolve", "Bind address resolve failed");

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

    try {
        acceptor.open(tcp::v4());
@@ -291,7 +291,7 @@ void MAVConnTCPServer::close() {
    if (!is_open())
        return;

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

    io_service.stop();
@@ -379,7 +379,7 @@ void MAVConnTCPServer::do_accept()
 void MAVConnTCPServer::async_accept_end(error_code error)
 {
    if (error) {
-       logError(PFXd "accept: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "accept: %s", channel, error.message().c_str());
        close();
        return;
    }
@@ -407,7 +407,7 @@ void MAVConnTCPServer::client_closed(boost::weak_ptr<MAVConnTCPClient> weak_inst
 {
    if (auto instp = weak_instp.lock()) {
        bool locked = mutex.try_lock();
-       logInform(PFXd "Client connection closed, channel: %d, address: %s",
+       CONSOLE_BRIDGE_logInform(PFXd "Client connection closed, channel: %d, address: %s",
                channel, instp->channel, to_string_ss(instp->server_ep).c_str());

        client_list.remove(instp);
diff --git a/src/udp.cpp b/src/udp.cpp
index 943ea78d9..9d12723c1 100644
--- a/src/udp.cpp
+++ b/src/udp.cpp
@@ -43,11 +43,11 @@ static bool resolve_address_udp(io_service &io, int chan, std::string host, unsi
        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 (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;
    }

@@ -68,15 +68,15 @@ MAVConnUDP::MAVConnUDP(uint8_t system_id, uint8_t component_id,
    if (!resolve_address_udp(io_service, channel, bind_host, bind_port, bind_ep))
        throw DeviceError("udp: resolve", "Bind address resolve failed");

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

    if (remote_host != "") {
        remote_exists = resolve_address_udp(io_service, channel, remote_host, remote_port, remote_ep);

        if (remote_exists)
-           logInform(PFXd "Remote address: %s", channel, to_string_ss(remote_ep).c_str());
+           CONSOLE_BRIDGE_logInform(PFXd "Remote address: %s", channel, to_string_ss(remote_ep).c_str());
        else
-           logWarn(PFXd "Remote address resolve failed.", channel);
+           CONSOLE_BRIDGE_logWarn(PFXd "Remote address resolve failed.", channel);
    }

    try {
@@ -123,12 +123,12 @@ void MAVConnUDP::close() {
 void MAVConnUDP::send_bytes(const uint8_t *bytes, size_t length)
 {
    if (!is_open()) {
-       logError(PFXd "send: channel closed!", channel);
+       CONSOLE_BRIDGE_logError(PFXd "send: channel closed!", channel);
        return;
    }

    if (!remote_exists) {
-       logDebug(PFXd "send: Remote not known, message dropped.", channel);
+       CONSOLE_BRIDGE_logDebug(PFXd "send: Remote not known, message dropped.", channel);
        return;
    }

@@ -145,16 +145,16 @@ void MAVConnUDP::send_message(const mavlink_message_t *message, uint8_t sysid, u
    assert(message != nullptr);

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

    if (!remote_exists) {
-       logDebug(PFXd "send: Remote not known, message dropped.", channel);
+       CONSOLE_BRIDGE_logDebug(PFXd "send: Remote not known, message dropped.", channel);
        return;
    }

-   logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+   CONSOLE_BRIDGE_logDebug(PFXd "send: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
            channel, message->msgid, message->len, sysid, compid, message->seq);

    MsgBuffer *buf = new_msgbuffer(message, sysid, compid);
@@ -182,13 +182,13 @@ void MAVConnUDP::async_receive_end(error_code error, size_t bytes_transferred)
    mavlink_status_t status;

    if (error) {
-       logError(PFXd "receive: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "receive: %s", channel, error.message().c_str());
        close();
        return;
    }

    if (remote_ep != last_remote_ep) {
-       logInform(PFXd "Remote address: %s", channel, to_string_ss(remote_ep).c_str());
+       CONSOLE_BRIDGE_logInform(PFXd "Remote address: %s", channel, to_string_ss(remote_ep).c_str());
        remote_exists = true;
        last_remote_ep = remote_ep;
    }
@@ -196,7 +196,7 @@ void MAVConnUDP::async_receive_end(error_code error, size_t bytes_transferred)
    iostat_rx_add(bytes_transferred);
    for (size_t i = 0; i < bytes_transferred; i++) {
        if (mavlink_parse_char(channel, rx_buf[i], &message, &status)) {
-           logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
+           CONSOLE_BRIDGE_logDebug(PFXd "recv: Message-Id: %d [%d bytes] Sys-Id: %d Comp-Id: %d Seq: %d",
                    channel, message.msgid, message.len, message.sysid, message.compid, message.seq);

            /* emit */ message_received(&message, message.sysid, message.compid);
@@ -229,11 +229,11 @@ void MAVConnUDP::do_sendto(bool check_tx_state)
 void MAVConnUDP::async_sendto_end(error_code error, size_t bytes_transferred)
 {
    if (error == boost::asio::error::network_unreachable) {
-       logWarn(PFXd "sendto: %s, retrying", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logWarn(PFXd "sendto: %s, retrying", channel, error.message().c_str());
        // do not return, try to resend
    }
    else if (error) {
-       logError(PFXd "sendto: %s", channel, error.message().c_str());
+       CONSOLE_BRIDGE_logError(PFXd "sendto: %s", channel, error.message().c_str());
        close();
        return;
    }