找回密码
 立即注册
首页 业界区 业界 AirSim+PX4+QGC实现无人机自动避障

AirSim+PX4+QGC实现无人机自动避障

赙浦 昨天 21:30
博客地址:https://www.cnblogs.com/zylyehuo/
参考链接: AirSim+PX4 无人机自动避障详细教程
AirSim 配置文件修改

代码修改完成后,进入 AirSim 根目录运行如下代码进行编译
  1. ./setup.sh
  2. ./build.sh
复制代码
运行完成后,将 Plugins 文件夹重新复制到 UE4 根目录下
MavLinkConnectionImpl.cpp
  1. // Copyright (c) Microsoft Corporation. All rights reserved.
  2. // Licensed under the MIT License.
  3. #include "MavLinkMessages.hpp"
  4. #include "MavLinkConnectionImpl.hpp"
  5. #include "Utils.hpp"
  6. #include "ThreadUtils.hpp"
  7. #include "../serial_com/Port.h"
  8. #include "../serial_com/SerialPort.hpp"
  9. #include "../serial_com/UdpClientPort.hpp"
  10. #include "../serial_com/TcpClientPort.hpp"
  11. using namespace mavlink_utils;
  12. using namespace mavlinkcom_impl;
  13. // hw-modify 全局字符串变量,用来在MavLinkMultirotorApi.hpp的update函数中打印调试信息。后续该改成正常打印的方式。
  14. std::string hw_extern_msg = Utils::stringf("---hw---: Global print string");
  15. MavLinkConnectionImpl::MavLinkConnectionImpl()
  16. {
  17.     // add our custom telemetry message length.
  18.     telemetry_.crc_errors = 0;
  19.     telemetry_.handler_microseconds = 0;
  20.     telemetry_.messages_handled = 0;
  21.     telemetry_.messages_received = 0;
  22.     telemetry_.messages_sent = 0;
  23.     closed = true;
  24.     ::memset(&mavlink_intermediate_status_, 0, sizeof(mavlink_status_t));
  25.     ::memset(&mavlink_status_, 0, sizeof(mavlink_status_t));
  26.     // todo: if we support signing then initialize
  27.     // mavlink_intermediate_status_.signing callbacks
  28. }
  29. std::string MavLinkConnectionImpl::getName()
  30. {
  31.     return name;
  32. }
  33. MavLinkConnectionImpl::~MavLinkConnectionImpl()
  34. {
  35.     con_.reset();
  36.     close();
  37. }
  38. std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::createConnection(const std::string& nodeName, std::shared_ptr<Port> port)
  39. {
  40.     // std::shared_ptr<MavLinkCom> owner, const std::string& nodeName
  41.     std::shared_ptr<MavLinkConnection> con = std::make_shared<MavLinkConnection>();
  42.     con->startListening(nodeName, port);
  43.     return con;
  44. }
  45. std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectLocalUdp(const std::string& nodeName, const std::string& localAddr, int localPort)
  46. {
  47.     std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
  48.     socket->connect(localAddr, localPort, "", 0);
  49.     return createConnection(nodeName, socket);
  50. }
  51. std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteAddr, int remotePort)
  52. {
  53.     std::string local = localAddr;
  54.     // just a little sanity check on the local address, if remoteAddr is localhost then localAddr must be also.
  55.     if (remoteAddr == "127.0.0.1") {
  56.         local = "127.0.0.1";
  57.     }
  58.     std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
  59.     socket->connect(local, 0, remoteAddr, remotePort);
  60.     return createConnection(nodeName, socket);
  61. }
  62. std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::string& nodeName, const std::string& localAddr, const std::string& remoteIpAddr, int remotePort)
  63. {
  64.     std::string local = localAddr;
  65.     // just a little sanity check on the local address, if remoteAddr is localhost then localAddr must be also.
  66.     if (remoteIpAddr == "127.0.0.1") {
  67.         local = "127.0.0.1";
  68.     }
  69.     std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
  70.     socket->connect(local, 0, remoteIpAddr, remotePort);
  71.     return createConnection(nodeName, socket);
  72. }
  73. std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr<MavLinkConnection> parent, const std::string& nodeName, const std::string& localAddr, int listeningPort)
  74. {
  75.     std::string local = localAddr;
  76.     close();
  77.     std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
  78.     port = socket; // this is so that a call to close() can cancel this blocking accept call.
  79.     socket->accept(localAddr, listeningPort);
  80.     std::string remote = socket->remoteAddress();
  81.     socket->setNonBlocking();
  82.     socket->setNoDelay();
  83.     parent->startListening(nodeName, socket);
  84.     return remote;
  85. }
  86. std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectSerial(const std::string& nodeName, const std::string& portName, int baudRate, const std::string& initString)
  87. {
  88.     std::shared_ptr<SerialPort> serial = std::make_shared<SerialPort>();
  89.     int hr = serial->connect(portName.c_str(), baudRate);
  90.     if (hr != 0)
  91.         throw std::runtime_error(Utils::stringf("Could not open the serial port %s, error=%d", portName.c_str(), hr));
  92.     // send this right away just in case serial link is not already configured
  93.     if (initString.size() > 0) {
  94.         serial->write(reinterpret_cast<const uint8_t*>(initString.c_str()), static_cast<int>(initString.size()));
  95.     }
  96.     return createConnection(nodeName, serial);
  97. }
  98. void MavLinkConnectionImpl::startListening(std::shared_ptr<MavLinkConnection> parent, const std::string& nodeName, std::shared_ptr<Port> connectedPort)
  99. {
  100.     name = nodeName;
  101.     con_ = parent;
  102.     if (port != connectedPort) {
  103.         close();
  104.         port = connectedPort;
  105.     }
  106.     closed = false;
  107.     Utils::cleanupThread(read_thread);
  108.     read_thread = std::thread{ &MavLinkConnectionImpl::readPackets, this };
  109.     Utils::cleanupThread(publish_thread_);
  110.     publish_thread_ = std::thread{ &MavLinkConnectionImpl::publishPackets, this };
  111. }
  112. // log every message that is "sent" using sendMessage.
  113. void MavLinkConnectionImpl::startLoggingSendMessage(std::shared_ptr<MavLinkLog> log)
  114. {
  115.     sendLog_ = log;
  116. }
  117. void MavLinkConnectionImpl::stopLoggingSendMessage()
  118. {
  119.     sendLog_ = nullptr;
  120. }
  121. // log every message that is "sent" using sendMessage.
  122. void MavLinkConnectionImpl::startLoggingReceiveMessage(std::shared_ptr<MavLinkLog> log)
  123. {
  124.     receiveLog_ = log;
  125. }
  126. void MavLinkConnectionImpl::stopLoggingReceiveMessage()
  127. {
  128.     receiveLog_ = nullptr;
  129. }
  130. void MavLinkConnectionImpl::close()
  131. {
  132.     closed = true;
  133.     if (port != nullptr) {
  134.         port->close();
  135.         port = nullptr;
  136.     }
  137.     if (read_thread.joinable()) {
  138.         read_thread.join();
  139.     }
  140.     if (publish_thread_.joinable()) {
  141.         msg_available_.post();
  142.         publish_thread_.join();
  143.     }
  144.     sendLog_ = nullptr;
  145.     receiveLog_ = nullptr;
  146. }
  147. bool MavLinkConnectionImpl::isOpen()
  148. {
  149.     return !closed;
  150. }
  151. int MavLinkConnectionImpl::getTargetComponentId()
  152. {
  153.     return this->other_component_id;
  154. }
  155. int MavLinkConnectionImpl::getTargetSystemId()
  156. {
  157.     return this->other_system_id;
  158. }
  159. uint8_t MavLinkConnectionImpl::getNextSequence()
  160. {
  161.     std::lock_guard<std::mutex> guard(buffer_mutex);
  162.     return next_seq++;
  163. }
  164. void MavLinkConnectionImpl::ignoreMessage(uint8_t message_id)
  165. {
  166.     ignored_messageids.insert(message_id);
  167. }
  168. void MavLinkConnectionImpl::sendMessage(const MavLinkMessage& m)
  169. {
  170.     if (ignored_messageids.find(m.msgid) != ignored_messageids.end())
  171.         return;
  172.     if (closed) {
  173.         return;
  174.     }
  175.     {
  176.         MavLinkMessage msg;
  177.         ::memcpy(&msg, &m, sizeof(MavLinkMessage));
  178.         prepareForSending(msg);
  179.         if (sendLog_ != nullptr) {
  180.             sendLog_->write(msg);
  181.         }
  182.         mavlink_message_t message;
  183.         message.compid = msg.compid;
  184.         message.sysid = msg.sysid;
  185.         message.len = msg.len;
  186.         message.checksum = msg.checksum;
  187.         message.magic = msg.magic;
  188.         message.incompat_flags = msg.incompat_flags;
  189.         message.compat_flags = msg.compat_flags;
  190.         message.seq = msg.seq;
  191.         message.msgid = msg.msgid;
  192.         ::memcpy(message.signature, msg.signature, 13);
  193.         ::memcpy(message.payload64, msg.payload64, PayloadSize * sizeof(uint64_t));
  194.         std::lock_guard<std::mutex> guard(buffer_mutex);
  195.         unsigned len = mavlink_msg_to_send_buffer(message_buf, &message);
  196. /*
  197.                 // hw-debug 打印要发送的mavlink报文内容, 132是距离传感器的ID
  198.                 if (message.msgid == 132)
  199.                 {
  200.                         unsigned char *p=message_buf;
  201.                         hw_extern_msg += Utils::stringf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:\n"
  202.                                 "%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X\n",
  203.                                 p[0],p[1],p[2],p[3],p[4],p[5],p[6],p[7],p[8],p[9],
  204.                                 p[10],p[11],p[12],p[13],p[14],p[15],p[16],p[17],p[18],p[19],
  205.                                 p[20],p[21],p[22],p[23],p[24]);
  206.                 }
  207. */
  208.         try {
  209.             port->write(message_buf, len);
  210.         }
  211.         catch (std::exception& e) {
  212.             throw std::runtime_error(Utils::stringf("MavLinkConnectionImpl: Error sending message on connection '%s', details: %s", name.c_str(), e.what()));
  213.         }
  214.     }
  215.     {
  216.         std::lock_guard<std::mutex> guard(telemetry_mutex_);
  217.         telemetry_.messages_sent++;
  218.     }
  219. }
  220. int MavLinkConnectionImpl::prepareForSending(MavLinkMessage& msg)
  221. {
  222.     // as per  https://github.com/mavlink/mavlink/blob/master/doc/MAVLink2.md
  223.     int seqno = getNextSequence();
  224.     bool mavlink1 = !supports_mavlink2_ && msg.protocol_version != 2;
  225.     bool signing = !mavlink1 && mavlink_status_.signing && (mavlink_status_.signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
  226.     uint8_t signature_len = signing ? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
  227.     uint8_t header_len = MAVLINK_CORE_HEADER_LEN + 1;
  228.     uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
  229.     if (mavlink1) {
  230.         msg.magic = MAVLINK_STX_MAVLINK1;
  231.         header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
  232.     }
  233.     else {
  234.         msg.magic = MAVLINK_STX;
  235.     }
  236.     msg.seq = seqno;
  237.     msg.incompat_flags = 0;
  238.     if (signing) {
  239.         msg.incompat_flags |= MAVLINK_IFLAG_SIGNED;
  240.     }
  241.     msg.compat_flags = 0;
  242.     // pack the payload buffer.
  243.     char* payload = reinterpret_cast<char*>(&msg.payload64[0]);
  244.     int len = msg.len;
  245.     // calculate checksum
  246.     const mavlink_msg_entry_t* entry = mavlink_get_msg_entry(msg.msgid);
  247.     uint8_t crc_extra = 0;
  248.     int msglen = 0;
  249.     if (entry != nullptr) {
  250.         crc_extra = entry->crc_extra;
  251.         msglen = entry->min_msg_len;
  252.     }
  253.     if (msg.msgid == MavLinkTelemetry::kMessageId) {
  254.         msglen = MavLinkTelemetry::MessageLength; // mavlink doesn't know about our custom telemetry message.
  255.     }
  256.     if (len != msglen) {
  257.         if (mavlink1) {
  258.             throw std::runtime_error(Utils::stringf("Message length %d doesn't match expected length%d\n", len, msglen));
  259.         }
  260.         else {
  261.             // mavlink2 supports trimming the payload of trailing zeros so the messages
  262.             // are variable length as a result.
  263.         }
  264.     }
  265.         // mavlink2版本的payload信息是可以变长的,结尾的0可以被去掉,接收方会自动补全
  266.         // _mav_trim_payload函数就是用来去掉结尾0的,但是原来的参数传递错误了,传的是msglen:_mav_trim_payload(payload, msglen)
  267.         // 而msglen是最小长度,由此导致传递的数据不完整。
  268.         // 应该传递的是实际数据长度,改成_mav_trim_payload(payload, len)
  269.     len = mavlink1 ? msglen : _mav_trim_payload(payload, len);
  270.     msg.len = len;
  271.     // form the header as a byte array for the crc
  272.     buf[0] = msg.magic;
  273.     buf[1] = msg.len;
  274.     if (mavlink1) {
  275.         buf[2] = msg.seq;
  276.         buf[3] = msg.sysid;
  277.         buf[4] = msg.compid;
  278.         buf[5] = msg.msgid & 0xFF;
  279.     }
  280.     else {
  281.         buf[2] = msg.incompat_flags;
  282.         buf[3] = msg.compat_flags;
  283.         buf[4] = msg.seq;
  284.         buf[5] = msg.sysid;
  285.         buf[6] = msg.compid;
  286.         buf[7] = msg.msgid & 0xFF;
  287.         buf[8] = (msg.msgid >> 8) & 0xFF;
  288.         buf[9] = (msg.msgid >> 16) & 0xFF;
  289.     }
  290.     msg.checksum = crc_calculate(&buf[1], header_len - 1);
  291.     crc_accumulate_buffer(&msg.checksum, payload, msg.len);
  292.     crc_accumulate(crc_extra, &msg.checksum);
  293.     // these macros use old style cast.
  294.     STRICT_MODE_OFF
  295.     mavlink_ck_a(&msg) = (uint8_t)(msg.checksum & 0xFF);
  296.     mavlink_ck_b(&msg) = (uint8_t)(msg.checksum >> 8);
  297.     STRICT_MODE_ON
  298.     if (signing) {
  299.         mavlink_sign_packet(mavlink_status_.signing,
  300.                             reinterpret_cast<uint8_t*>(msg.signature),
  301.                             reinterpret_cast<const uint8_t*>(message_buf),
  302.                             header_len,
  303.                             reinterpret_cast<const uint8_t*>(payload),
  304.                             msg.len,
  305.                             reinterpret_cast<const uint8_t*>(payload) + msg.len);
  306.     }
  307.     return msg.len + header_len + 2 + signature_len;
  308. }
  309. void MavLinkConnectionImpl::sendMessage(const MavLinkMessageBase& msg)
  310. {
  311.     MavLinkMessage m;
  312.     msg.encode(m);
  313.     sendMessage(m);
  314. }
  315. int MavLinkConnectionImpl::subscribe(MessageHandler handler)
  316. {
  317.     MessageHandlerEntry entry{ static_cast<int>(listeners.size() + 1), handler };
  318.     std::lock_guard<std::mutex> guard(listener_mutex);
  319.     listeners.push_back(entry);
  320.     snapshot_stale = true;
  321.     return entry.id;
  322. }
  323. void MavLinkConnectionImpl::unsubscribe(int id)
  324. {
  325.     std::lock_guard<std::mutex> guard(listener_mutex);
  326.     for (auto ptr = listeners.begin(), end = listeners.end(); ptr != end; ptr++) {
  327.         if ((*ptr).id == id) {
  328.             listeners.erase(ptr);
  329.             snapshot_stale = true;
  330.             break;
  331.         }
  332.     }
  333. }
  334. void MavLinkConnectionImpl::joinLeftSubscriber(std::shared_ptr<MavLinkConnection> remote, std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
  335. {
  336.     unused(connection);
  337.     // forward messages from our connected node to the remote proxy.
  338.     if (supports_mavlink2_) {
  339.         // tell the remote connection to expect mavlink2 messages.
  340.         remote->pImpl->supports_mavlink2_ = true;
  341.     }
  342.     remote->sendMessage(msg);
  343. }
  344. void MavLinkConnectionImpl::joinRightSubscriber(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
  345. {
  346.     unused(connection);
  347.     // forward messages from remote proxy to local connected node
  348.     this->sendMessage(msg);
  349. }
  350. void MavLinkConnectionImpl::join(std::shared_ptr<MavLinkConnection> remote, bool subscribeToLeft, bool subscribeToRight)
  351. {
  352.     if (subscribeToLeft)
  353.         this->subscribe(std::bind(&MavLinkConnectionImpl::joinLeftSubscriber, this, remote, std::placeholders::_1, std::placeholders::_2));
  354.     if (subscribeToRight)
  355.         remote->subscribe(std::bind(&MavLinkConnectionImpl::joinRightSubscriber, this, std::placeholders::_1, std::placeholders::_2));
  356. }
  357. void MavLinkConnectionImpl::readPackets()
  358. {
  359.     //CurrentThread::setMaximumPriority();
  360.     CurrentThread::setThreadName("MavLinkThread");
  361.     std::shared_ptr<Port> safePort = this->port;
  362.     mavlink_message_t msg;
  363.     mavlink_message_t msgBuffer; // intermediate state.
  364.     const int MAXBUFFER = 512;
  365.     uint8_t* buffer = new uint8_t[MAXBUFFER];
  366.     mavlink_intermediate_status_.parse_state = MAVLINK_PARSE_STATE_IDLE;
  367.     int channel = 0;
  368.     int hr = 0;
  369.     while (hr == 0 && con_ != nullptr && !closed) {
  370.         int read = 0;
  371.         if (safePort->isClosed()) {
  372.             // hmmm, wait till it is opened?
  373.             std::this_thread::sleep_for(std::chrono::milliseconds(10));
  374.             continue;
  375.         }
  376.         int count = safePort->read(buffer, MAXBUFFER);
  377.         if (count <= 0) {
  378.             // error? well let's try again, but we should be careful not to spin too fast and kill the CPU
  379.             std::this_thread::sleep_for(std::chrono::milliseconds(1));
  380.             continue;
  381.         }
  382.         for (int i = 0; i < count; i++) {
  383.             uint8_t frame_state = mavlink_frame_char_buffer(&msgBuffer, &mavlink_intermediate_status_, buffer[i], &msg, &mavlink_status_);
  384.             if (frame_state == MAVLINK_FRAMING_INCOMPLETE) {
  385.                 continue;
  386.             }
  387.             else if (frame_state == MAVLINK_FRAMING_BAD_CRC) {
  388.                 std::lock_guard<std::mutex> guard(telemetry_mutex_);
  389.                 telemetry_.crc_errors++;
  390.             }
  391.             else if (frame_state == MAVLINK_FRAMING_OK) {
  392.                 // pick up the sysid/compid of the remote node we are connected to.
  393.                 if (other_system_id == -1) {
  394.                     other_system_id = msg.sysid;
  395.                     other_component_id = msg.compid;
  396.                 }
  397.                 if (mavlink_intermediate_status_.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
  398.                     // then this is a mavlink 1 message
  399.                 }
  400.                 else if (!supports_mavlink2_) {
  401.                     // then this mavlink sender supports mavlink 2
  402.                     supports_mavlink2_ = true;
  403.                 }
  404.                 if (con_ != nullptr && !closed) {
  405.                     {
  406.                         std::lock_guard<std::mutex> guard(telemetry_mutex_);
  407.                         telemetry_.messages_received++;
  408.                     }
  409.                     // queue event for publishing.
  410.                     {
  411.                         std::lock_guard<std::mutex> guard(msg_queue_mutex_);
  412.                         MavLinkMessage message;
  413.                         message.compid = msg.compid;
  414.                         message.sysid = msg.sysid;
  415.                         message.len = msg.len;
  416.                         message.checksum = msg.checksum;
  417.                         message.magic = msg.magic;
  418.                         message.incompat_flags = msg.incompat_flags;
  419.                         message.compat_flags = msg.compat_flags;
  420.                         message.seq = msg.seq;
  421.                         message.msgid = msg.msgid;
  422.                         message.protocol_version = supports_mavlink2_ ? 2 : 1;
  423.                         ::memcpy(message.signature, msg.signature, 13);
  424.                         ::memcpy(message.payload64, msg.payload64, PayloadSize * sizeof(uint64_t));
  425.                         msg_queue_.push(message);
  426.                     }
  427.                     if (waiting_for_msg_) {
  428.                         msg_available_.post();
  429.                     }
  430.                 }
  431.             }
  432.             else {
  433.                 std::lock_guard<std::mutex> guard(telemetry_mutex_);
  434.                 telemetry_.crc_errors++;
  435.             }
  436.         }
  437.     } //while
  438.     delete[] buffer;
  439. } //readPackets
  440. void MavLinkConnectionImpl::drainQueue()
  441. {
  442.     MavLinkMessage message;
  443.     bool hasMsg = true;
  444.     while (hasMsg) {
  445.         hasMsg = false;
  446.         {
  447.             std::lock_guard<std::mutex> guard(msg_queue_mutex_);
  448.             if (!msg_queue_.empty()) {
  449.                 message = msg_queue_.front();
  450.                 msg_queue_.pop();
  451.                 hasMsg = true;
  452.             }
  453.         }
  454.         if (!hasMsg) {
  455.             return;
  456.         }
  457.         if (receiveLog_ != nullptr) {
  458.             receiveLog_->write(message);
  459.         }
  460.         // publish the message from this thread, this is safer than publishing from the readPackets thread
  461.         // as it ensures we don't lose messages if the listener is slow.
  462.         if (snapshot_stale) {
  463.             // this is tricky, the clear has to be done outside the lock because it is destructing the handlers
  464.             // and the handler might try and call unsubscribe, which needs to be able to grab the lock, otherwise
  465.             // we would get a deadlock.
  466.             snapshot.clear();
  467.             std::lock_guard<std::mutex> guard(listener_mutex);
  468.             snapshot = listeners;
  469.             snapshot_stale = false;
  470.         }
  471.         auto end = snapshot.end();
  472.         if (message.msgid == static_cast<uint8_t>(MavLinkMessageIds::MAVLINK_MSG_ID_AUTOPILOT_VERSION)) {
  473.             MavLinkAutopilotVersion cap;
  474.             cap.decode(message);
  475.             if ((cap.capabilities & MAV_PROTOCOL_CAPABILITY_MAVLINK2) != 0) {
  476.                 this->supports_mavlink2_ = true;
  477.             }
  478.         }
  479.         auto startTime = std::chrono::system_clock::now();
  480.         std::shared_ptr<MavLinkConnection> sharedPtr = std::shared_ptr<MavLinkConnection>(this->con_);
  481.         for (auto ptr = snapshot.begin(); ptr != end; ptr++) {
  482.             try {
  483.                 (*ptr).handler(sharedPtr, message);
  484.             }
  485.             catch (std::exception& e) {
  486.                 Utils::log(Utils::stringf("MavLinkConnectionImpl: Error handling message %d on connection '%s', details: %s",
  487.                                           message.msgid,
  488.                                           name.c_str(),
  489.                                           e.what()),
  490.                            Utils::kLogLevelError);
  491.             }
  492.         }
  493.         {
  494.             auto endTime = std::chrono::system_clock::now();
  495.             auto diff = endTime - startTime;
  496.             long microseconds = static_cast<long>(std::chrono::duration_cast<std::chrono::microseconds>(diff).count());
  497.             std::lock_guard<std::mutex> guard(telemetry_mutex_);
  498.             telemetry_.messages_handled++;
  499.             telemetry_.handler_microseconds += microseconds;
  500.         }
  501.     }
  502. }
  503. void MavLinkConnectionImpl::publishPackets()
  504. {
  505.     //CurrentThread::setMaximumPriority();
  506.     CurrentThread::setThreadName("MavLinkThread");
  507.     publish_thread_id_ = std::this_thread::get_id();
  508.     while (!closed) {
  509.         drainQueue();
  510.         waiting_for_msg_ = true;
  511.         msg_available_.wait();
  512.         waiting_for_msg_ = false;
  513.     }
  514. }
  515. bool MavLinkConnectionImpl::isPublishThread() const
  516. {
  517.     return std::this_thread::get_id() == publish_thread_id_;
  518. }
  519. void MavLinkConnectionImpl::getTelemetry(MavLinkTelemetry& result)
  520. {
  521.     std::lock_guard<std::mutex> guard(telemetry_mutex_);
  522.     result = telemetry_;
  523.     // reset counters
  524.     telemetry_.crc_errors = 0;
  525.     telemetry_.handler_microseconds = 0;
  526.     telemetry_.messages_handled = 0;
  527.     telemetry_.messages_received = 0;
  528.     telemetry_.messages_sent = 0;
  529.     if (telemetry_.wifiInterfaceName != nullptr) {
  530.         telemetry_.wifi_rssi = port->getRssi(telemetry_.wifiInterfaceName);
  531.     }
  532. }
复制代码
MavLinkMultirotorApi.hpp

[code]// Copyright (c) Microsoft Corporation. All rights reserved.// Licensed under the MIT License.#ifndef msr_airlib_MavLinkDroneController_hpp#define msr_airlib_MavLinkDroneController_hpp#include "MavLinkConnection.hpp"#include "MavLinkMessages.hpp"#include "MavLinkNode.hpp"#include "MavLinkVehicle.hpp"#include "MavLinkVideoStream.hpp"#include #include #include #include #include #include #include #include #include "common/AirSimSettings.hpp"#include "common/Common.hpp"#include "common/CommonStructs.hpp"#include "common/PidController.hpp"#include "common/VectorMath.hpp"#include "common/common_utils/FileSystem.hpp"#include "common/common_utils/SmoothingFilter.hpp"#include "common/common_utils/Timer.hpp"#include "physics/World.hpp"#include "sensors/SensorCollection.hpp"#include "vehicles/multirotor/api/MultirotorApiBase.hpp"//sensors#include "sensors/barometer/BarometerBase.hpp"#include "sensors/distance/DistanceSimple.hpp"#include "sensors/gps/GpsBase.hpp"#include "sensors/imu/ImuBase.hpp"#include "sensors/magnetometer/MagnetometerBase.hpp"// hw-modify 调试信息开关#define HW_DEBUG_MSG        0// hw-modify 目前只会在本文件中用addStatusMessage进行打印, 因此其他所有模块的打开都由本文件负责. 临时修改,后续要完善// 在MavLinkConnectionImpl.cpp中定义了全局变量hw_extern_msg, 其他模块向该变量中写入要打印的内容// 本模块的update函数中会循环打印该字符串的值. 每次打印后都会清空该字符串extern std::string hw_extern_msg;namespace msr{namespace airlib{    class MavLinkMultirotorApi : public MultirotorApiBase    {    public: //methods        virtual ~MavLinkMultirotorApi()        {            closeAllConnection();            if (this->connect_thread_.joinable()) {                this->connect_thread_.join();            }            if (this->telemetry_thread_.joinable()) {                this->telemetry_thread_.join();            }        }        //non-base interface specific to MavLinKDroneController        void initialize(const AirSimSettings::MavLinkConnectionInfo& connection_info, const SensorCollection* sensors, bool is_simulation)        {            connection_info_ = connection_info;            sensors_ = sensors;            is_simulation_mode_ = is_simulation;            lock_step_enabled_ = connection_info.lock_step;            try {                openAllConnections();                is_ready_ = true;            }            catch (std::exception& ex) {                is_ready_ = false;                is_ready_message_ = Utils::stringf("Failed to connect: %s", ex.what());            }        }        Pose getMocapPose()        {            std::lock_guard guard(mocap_pose_mutex_);            return mocap_pose_;        }        virtual const SensorCollection& getSensors() const override        {            return *sensors_;        }        //reset PX4 stack        virtual void resetImplementation() override        {            // note this is called AFTER "initialize" when we've connected to the drone            // so this method cannot reset any of that connection state.            world_ = nullptr;            for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) {                if (container->getName() == "World") {                    // cool beans!                    // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason...                    world_ = static_cast(container);                }            }            MultirotorApiBase::resetImplementation();            was_reset_ = true;        }        unsigned long long getSimTime()        {            // This ensures HIL_SENSOR and HIL_GPS have matching clocks.            if (lock_step_active_) {                if (sim_time_us_ == 0) {                    sim_time_us_ = clock()->nowNanos() / 1000;                }                return sim_time_us_;            }            else {                return clock()->nowNanos() / 1000;            }        }        void advanceTime()        {            sim_time_us_ = clock()->nowNanos() / 1000;        }        //update sensors in PX4 stack        virtual void update() override        {                // hw-modify 打印全局字符串,打印完成后清空                if (hw_extern_msg.length())                {                        addStatusMessage(hw_extern_msg);                                hw_extern_msg.clear();                }                                    try {                auto now = clock()->nowNanos() / 1000;                MultirotorApiBase::update();                if (sensors_ == nullptr || !connected_ || connection_ == nullptr || !connection_->isOpen() || !got_first_heartbeat_)                    return;                {                    std::lock_guard guard(telemetry_mutex_);                    update_count_++;                }                if (lock_step_active_) {                    if (last_update_time_ + 1000000 < now) {                        // if 1 second passes then something is terribly wrong, reset lockstep mode                        lock_step_active_ = false;                        {                            std::lock_guard guard(telemetry_mutex_);                            lock_step_resets_++;                        }                        addStatusMessage("timeout on HilActuatorControlsMessage, resetting lock step mode");                    }                    else if (!received_actuator_controls_) {                        // drop this one since we are in LOCKSTEP mode and we have not yet received the HilActuatorControlsMessage.                        return;                    }                }                last_update_time_ = now;                {                    std::lock_guard guard(telemetry_mutex_);                    hil_sensor_count_++;                }                advanceTime();                //send sensor updates                const auto& imu_output = getImuData("");                const auto& mag_output = getMagnetometerData("");                const auto& baro_output = getBarometerData("");                sendHILSensor(imu_output.linear_acceleration,                              imu_output.angular_velocity,                              mag_output.magnetic_field_body,                              baro_output.pressure * 0.01f /*Pa to Millibar */,                              baro_output.altitude);                sendSystemTime();                                #if 0                const uint count_distance_sensors = getSensors().size(SensorBase::SensorType:istance);                if (count_distance_sensors != 0) {                    const auto* distance_sensor = static_cast(                        sensors_->getByType(SensorBase::SensorType:istance));                    // Don't send the data if sending to external controller is disabled in settings                    if (distance_sensor && distance_sensor->getParams().external_controller) {                        const auto& distance_output = distance_sensor->getOutput();                        sendDistanceSensor(distance_output.min_distance * 100, //m -> cm                                           distance_output.max_distance * 100, //m -> cm                                           distance_output.distance * 100, //m-> cm                                           0, //sensor type: //TODO: allow changing in settings?                                           77, //sensor id, //TODO: should this be something real?                                           distance_output.relative_pose.orientation); //TODO: convert from radians to degrees?                    }                }                                #else                                // hw-modify 遍历所有传感器并发送到px4,以前的逻辑只处理了第一个传感器                const uint count_distance_sensors = getSensors().size(SensorBase::SensorType:istance);                if (count_distance_sensors != 0) {                                        for (uint i=0; igetByType(SensorBase::SensorType:istance, i));                            // Don't send the data if sending to external controller is disabled in settings                            if (distance_sensor && distance_sensor->getParams().external_controller) {                                const auto& distance_output = distance_sensor->getOutput();                                                // 调试信息                                                #if (HW_DEBUG_MSG)                                                auto msg = Utils::stringf("distance_sensor(%d): min=%f, max=%f, distance=%f, 4.w=%f, 4.x=%f, 4.y=%f, 4.z=%f",                                                         i, distance_output.min_distance, distance_output.max_distance, distance_output.distance,                                                        distance_output.relative_pose.orientation.w(), distance_output.relative_pose.orientation.x(),                                                         distance_output.relative_pose.orientation.y(), distance_output.relative_pose.orientation.z());                                                addStatusMessage(msg);                                                msg = Utils::stringf("aram: min=%f, max=%f, x=%f, y=%f, z=%f, roll=%f, pitch=%f, yaw=%f\n\n",                                                 distance_sensor->getParams().min_distance, distance_sensor->getParams().max_distance,                                                distance_sensor->getParams().relative_pose.position.x(),distance_sensor->getParams().relative_pose.position.y(),distance_sensor->getParams().relative_pose.position.z(),                                                distance_sensor->getParams().relative_pose.orientation.x(),distance_sensor->getParams().relative_pose.orientation.y(),distance_sensor->getParams().relative_pose.orientation.z());                                                addStatusMessage(msg);                                                #endif                        sendDistanceSensor(distance_output.min_distance * 100, //m -> cm                                           distance_output.max_distance * 100, //m -> cm                                           distance_output.distance * 100, //m-> cm                                           0, //sensor type, https://mavlink.io/zh/messages/common.html#MAV_DISTANCE_SENSOR 描述了支持的传感器类型                                           (uint8_t)i+1, // sensor id, 使用i+1作为传感器索引,区分不同传感器                                           distance_output.relative_pose.orientation); // 直接使用当前的sin半角数值,不用转换成角度单位的值                            }                                        }                }                                #endif                const uint count_gps_sensors = getSensors().size(SensorBase::SensorType::Gps);                if (count_gps_sensors != 0) {                    const auto& gps_output = getGpsData("");                    //send GPS                    if (gps_output.is_valid && gps_output.gnss.time_utc > last_gps_time_) {                        last_gps_time_ = gps_output.gnss.time_utc;                        Vector3r gps_velocity = gps_output.gnss.velocity;                        Vector3r gps_velocity_xy = gps_velocity;                        gps_velocity_xy.z() = 0;                        float gps_cog;                        if (Utils::isApproximatelyZero(gps_velocity.y(), 1E-2f) && Utils::isApproximatelyZero(gps_velocity.x(), 1E-2f))                            gps_cog = 0;                        else                            gps_cog = Utils::radiansToDegrees(atan2(gps_velocity.y(), gps_velocity.x()));                        if (gps_cog < 0)                            gps_cog += 360;                        sendHILGps(gps_output.gnss.geo_point, gps_velocity, gps_velocity_xy.norm(), gps_cog, gps_output.gnss.eph, gps_output.gnss.epv, gps_output.gnss.fix_type, 10);                    }                }                auto end = clock()->nowNanos() / 1000;                {                    std::lock_guard guard(telemetry_mutex_);                    update_time_ += (end - now);                }            }            catch (std::exception& e) {                addStatusMessage("Exception sending messages to vehicle");                addStatusMessage(e.what());                disconnect();                connect(); // re-start a new connection so PX4 can be restarted and AirSim will happily continue on.            }            //must be done at the end            if (was_reset_)                was_reset_ = false;        }        virtual bool isReady(std::string& message) const override        {            if (!is_ready_ && is_ready_message_.size() > 0) {                message = is_ready_message_;            }            return is_ready_;        }        virtual bool canArm() const override        {            return is_ready_ && has_gps_lock_;        }        //TODO: this method can't be const yet because it clears previous messages        virtual void getStatusMessages(std::vector& messages) override        {            updateState();            //clear param            messages.clear();            //move messages from private vars to param            std::lock_guard guard(status_text_mutex_);            while (!status_messages_.empty()) {                messages.push_back(status_messages_.front());                status_messages_.pop();            }        }        virtual Kinematics::State getKinematicsEstimated() const override        {            updateState();            Kinematics::State state;            //TODO: reduce code duplication in getPosition() etc methods?            state.pose.position = Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z);            state.pose.orientation = VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw);            state.twist.linear = Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z);            state.twist.angular = Vector3r(current_state_.attitude.roll_rate, current_state_.attitude.pitch_rate, current_state_.attitude.yaw_rate);            state.accelerations.linear = Vector3r(current_state_.local_est.acc.x, current_state_.local_est.acc.y, current_state_.local_est.acc.z);            //TODO: how do we get angular acceleration?            return state;        }        virtual bool isApiControlEnabled() const override        {            return is_api_control_enabled_;        }        virtual void enableApiControl(bool is_enabled) override        {            checkValidVehicle();            if (is_enabled) {                mav_vehicle_->requestControl();                is_api_control_enabled_ = true;            }            else {                mav_vehicle_->releaseControl();                is_api_control_enabled_ = false;            }        }        virtual Vector3r getPosition() const override        {            updateState();            return Vector3r(current_state_.local_est.pos.x, current_state_.local_est.pos.y, current_state_.local_est.pos.z);        }        virtual Vector3r getVelocity() const override        {            updateState();            return Vector3r(current_state_.local_est.lin_vel.x, current_state_.local_est.lin_vel.y, current_state_.local_est.lin_vel.z);        }        virtual Quaternionr getOrientation() const override        {            updateState();            return VectorMath::toQuaternion(current_state_.attitude.pitch, current_state_.attitude.roll, current_state_.attitude.yaw);        }        virtual LandedState getLandedState() const override        {            updateState();            return current_state_.controls.landed ? LandedState:anded : LandedState::Flying;        }        virtual real_T getActuation(unsigned int rotor_index) const override        {            if (!is_simulation_mode_)                throw std::logic_error("Attempt to read motor controls while not in simulation mode");            std::lock_guard guard(hil_controls_mutex_);            return rotor_controls_[rotor_index];        }        virtual size_t getActuatorCount() const override        {            return RotorControlsCount;        }        virtual bool armDisarm(bool arm) override        {            SingleCall lock(this);            checkValidVehicle();            bool rc = false;            if (arm) {                float timeout_sec = 10;                waitForHomeLocation(timeout_sec);                waitForStableGroundPosition(timeout_sec);            }            mav_vehicle_->armDisarm(arm).wait(10000, &rc);            return rc;        }        void onArmed()        {            if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) {                auto con = mav_vehicle_->getConnection();                if (con != nullptr) {                    if (log_ != nullptr) {                        log_->close();                        log_ = nullptr;                    }                    try {                        std::time_t t = std::time(0); // get time now                        std::tm* now = std::localtime(&t);                        auto folder = Utils::stringf("%04d-%02d-%02d", now->tm_year + 1900, now->tm_mon + 1, now->tm_mday);                        auto path = common_utils::FileSystem::ensureFolder(connection_info_.logs, folder);                        auto filename = Utils::stringf("%02d-%02d-%02d.mavlink", now->tm_hour, now->tm_min, now->tm_sec);                        auto fullpath = common_utils::FileSystem::combine(path, filename);                        addStatusMessage(Utils::stringf("Opening log file: %s", fullpath.c_str()));                        log_file_name_ = fullpath;                        log_ = std::make_shared();                        log_->openForWriting(fullpath, false);                        con->startLoggingSendMessage(log_);                        con->startLoggingReceiveMessage(log_);                        if (con != connection_) {                            // log the SITL channel also                            connection_->startLoggingSendMessage(log_);                            connection_->startLoggingReceiveMessage(log_);                        }                        start_telemtry_thread();                    }                    catch (std::exception& ex) {                        addStatusMessage(std::string("Opening log file failed: ") + ex.what());                    }                }            }        }        void onDisarmed()        {            if (connection_info_.logs.size() > 0 && mav_vehicle_ != nullptr) {                auto con = mav_vehicle_->getConnection();                if (con != nullptr) {                    con->stopLoggingSendMessage();                    con->stopLoggingReceiveMessage();                }                if (connection_ != nullptr) {                    connection_->stopLoggingSendMessage();                    connection_->stopLoggingReceiveMessage();                }            }            if (log_ != nullptr) {                addStatusMessage(Utils::stringf("Closing log file: %s", log_file_name_.c_str()));                log_->close();                log_ = nullptr;            }        }        void waitForHomeLocation(float timeout_sec)        {            if (!current_state_.home.is_set) {                addStatusMessage("Waiting for valid GPS home location...");                if (!waitForFunction([&]() {                         return current_state_.home.is_set;                     },                                     timeout_sec)                         .isComplete()) {                    throw VehicleMoveException("Vehicle does not have a valid GPS home location");                }            }        }        void waitForStableGroundPosition(float timeout_sec)        {            // wait for ground stabilization            if (ground_variance_ > GroundTolerance) {                addStatusMessage("Waiting for z-position to stabilize...");                if (!waitForFunction([&]() {                         return ground_variance_ takeoff(z, 0.0f /* pitch */, yaw).wait(static_cast(timeout_sec * 1000), &rc)) {                throw VehicleMoveException("TakeOff command - timeout waiting for response");            }            if (!rc) {                throw VehicleMoveException("TakeOff command rejected by drone");            }            if (timeout_sec
您需要登录后才可以回帖 登录 | 立即注册