From e764c68d0aec7818e9f14384f325a79068b44d38 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Wed, 22 Apr 2015 11:08:19 -0700 Subject: [PATCH] mavlink: consolidated nuttx and posix changes Removed nuttx and posix specific files for mavlink_ftp and mavlink_receiver. Signed-off-by: Mark Charlebois --- ...{mavlink_ftp_posix.cpp => mavlink_ftp.cpp} | 7 +- src/modules/mavlink/mavlink_ftp_nuttx.cpp | 853 --------- ...eceiver_posix.cpp => mavlink_receiver.cpp} | 9 +- .../mavlink/mavlink_receiver_nuttx.cpp | 1590 ----------------- src/modules/mavlink/mavlink_tests/module.mk | 6 +- src/modules/mavlink/module.mk | 12 +- 6 files changed, 19 insertions(+), 2458 deletions(-) rename src/modules/mavlink/{mavlink_ftp_posix.cpp => mavlink_ftp.cpp} (99%) delete mode 100644 src/modules/mavlink/mavlink_ftp_nuttx.cpp rename src/modules/mavlink/{mavlink_receiver_posix.cpp => mavlink_receiver.cpp} (99%) delete mode 100644 src/modules/mavlink/mavlink_receiver_nuttx.cpp diff --git a/src/modules/mavlink/mavlink_ftp_posix.cpp b/src/modules/mavlink/mavlink_ftp.cpp similarity index 99% rename from src/modules/mavlink/mavlink_ftp_posix.cpp rename to src/modules/mavlink/mavlink_ftp.cpp index 1ff7dce735..4d644a8627 100644 --- a/src/modules/mavlink/mavlink_ftp_posix.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -820,7 +820,12 @@ MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length return -1; } - dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY, 0x0777); + dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY +// POSIX requires the permissions to be supplied if O_CREAT passed +#ifdef __PX4_POSIX + , 0x0777 +#endif + ); if (dst_fd < 0) { op_errno = errno; ::close(src_fd); diff --git a/src/modules/mavlink/mavlink_ftp_nuttx.cpp b/src/modules/mavlink/mavlink_ftp_nuttx.cpp deleted file mode 100644 index 4ba595a87b..0000000000 --- a/src/modules/mavlink/mavlink_ftp_nuttx.cpp +++ /dev/null @@ -1,853 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/// @file mavlink_ftp.cpp -/// @author px4dev, Don Gagne - -#include -#include -#include -#include -#include -#include - -#include "mavlink_ftp.h" -#include "mavlink_tests/mavlink_ftp_test.h" - -// Uncomment the line below to get better debug output. Never commit with this left on. -//#define MAVLINK_FTP_DEBUG - -MavlinkFTP * -MavlinkFTP::get_server(void) -{ - static MavlinkFTP server; - return &server; -} - -MavlinkFTP::MavlinkFTP() : - _request_bufs{}, - _request_queue{}, - _request_queue_sem{}, - _utRcvMsgFunc{}, - _ftp_test{} -{ - // initialise the request freelist - dq_init(&_request_queue); - sem_init(&_request_queue_sem, 0, 1); - - // initialize session list - for (size_t i=0; imsgid == MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { - mavlink_msg_file_transfer_protocol_decode(msg, &req->message); - -#ifdef MAVLINK_FTP_UNIT_TEST - if (!_utRcvMsgFunc) { - warnx("Incorrectly written unit test\n"); - return; - } - // We use fake ids when unit testing - req->serverSystemId = MavlinkFtpTest::serverSystemId; - req->serverComponentId = MavlinkFtpTest::serverComponentId; - req->serverChannel = MavlinkFtpTest::serverChannel; -#else - // Not unit testing, use the real thing - req->serverSystemId = mavlink->get_system_id(); - req->serverComponentId = mavlink->get_component_id(); - req->serverChannel = mavlink->get_channel(); -#endif - - // This is the system id we want to target when sending - req->targetSystemId = msg->sysid; - - if (req->message.target_system == req->serverSystemId) { - req->mavlink = mavlink; -#ifdef MAVLINK_FTP_UNIT_TEST - // We are running in Unit Test mode. Don't queue, just call _worket directly. - _process_request(req); -#else - // We are running in normal mode. Queue the request to the worker - work_queue(LPWORK, &req->work, &MavlinkFTP::_worker_trampoline, req, 0); -#endif - return; - } - } - - _return_request(req); -} - -/// @brief Queued static work queue routine to handle mavlink messages -void -MavlinkFTP::_worker_trampoline(void *arg) -{ - Request* req = reinterpret_cast(arg); - MavlinkFTP* server = MavlinkFTP::get_server(); - - // call the server worker with the work item - server->_process_request(req); -} - -/// @brief Processes an FTP message -void -MavlinkFTP::_process_request(Request *req) -{ - PayloadHeader *payload = reinterpret_cast(&req->message.payload[0]); - - ErrorCode errorCode = kErrNone; - - // basic sanity checks; must validate length before use - if (payload->size > kMaxDataLength) { - errorCode = kErrInvalidDataSize; - goto out; - } - -#ifdef MAVLINK_FTP_DEBUG - printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset); -#endif - - switch (payload->opcode) { - case kCmdNone: - break; - - case kCmdTerminateSession: - errorCode = _workTerminate(payload); - break; - - case kCmdResetSessions: - errorCode = _workReset(payload); - break; - - case kCmdListDirectory: - errorCode = _workList(payload); - break; - - case kCmdOpenFileRO: - errorCode = _workOpen(payload, O_RDONLY); - break; - - case kCmdCreateFile: - errorCode = _workOpen(payload, O_CREAT | O_EXCL | O_WRONLY); - break; - - case kCmdOpenFileWO: - errorCode = _workOpen(payload, O_CREAT | O_WRONLY); - break; - - case kCmdReadFile: - errorCode = _workRead(payload); - break; - - case kCmdWriteFile: - errorCode = _workWrite(payload); - break; - - case kCmdRemoveFile: - errorCode = _workRemoveFile(payload); - break; - - case kCmdRename: - errorCode = _workRename(payload); - break; - - case kCmdTruncateFile: - errorCode = _workTruncateFile(payload); - break; - - case kCmdCreateDirectory: - errorCode = _workCreateDirectory(payload); - break; - - case kCmdRemoveDirectory: - errorCode = _workRemoveDirectory(payload); - break; - - - case kCmdCalcFileCRC32: - errorCode = _workCalcFileCRC32(payload); - break; - - default: - errorCode = kErrUnknownCommand; - break; - } - -out: - // handle success vs. error - if (errorCode == kErrNone) { - payload->req_opcode = payload->opcode; - payload->opcode = kRspAck; -#ifdef MAVLINK_FTP_DEBUG - warnx("FTP: ack\n"); -#endif - } else { - int r_errno = errno; - warnx("FTP: nak %u", errorCode); - payload->req_opcode = payload->opcode; - payload->opcode = kRspNak; - payload->size = 1; - payload->data[0] = errorCode; - if (errorCode == kErrFailErrno) { - payload->size = 2; - payload->data[1] = r_errno; - } - } - - - // respond to the request - _reply(req); - - _return_request(req); -} - -/// @brief Sends the specified FTP reponse message out through mavlink -void -MavlinkFTP::_reply(Request *req) -{ - PayloadHeader *payload = reinterpret_cast(&req->message.payload[0]); - - payload->seqNumber = payload->seqNumber + 1; - - mavlink_message_t msg; - msg.checksum = 0; -#ifndef MAVLINK_FTP_UNIT_TEST - uint16_t len = -#endif - mavlink_msg_file_transfer_protocol_pack_chan(req->serverSystemId, // Sender system id - req->serverComponentId, // Sender component id - req->serverChannel, // Channel to send on - &msg, // Message to pack payload into - 0, // Target network - req->targetSystemId, // Target system id - 0, // Target component id - (const uint8_t*)payload); // Payload to pack into message - - bool success = true; -#ifdef MAVLINK_FTP_UNIT_TEST - // Unit test hook is set, call that instead - _utRcvMsgFunc(&msg, _ftp_test); -#else - Mavlink *mavlink = req->mavlink; - - mavlink->lockMessageBufferMutex(); - success = mavlink->message_buffer_write(&msg, len); - mavlink->unlockMessageBufferMutex(); - -#endif - - if (!success) { - warnx("FTP TX ERR"); - } -#ifdef MAVLINK_FTP_DEBUG - else { - warnx("wrote: sys: %d, comp: %d, chan: %d, checksum: %d", - req->serverSystemId, - req->serverComponentId, - req->serverChannel, - msg.checksum); - } -#endif -} - -/// @brief Responds to a List command -MavlinkFTP::ErrorCode -MavlinkFTP::_workList(PayloadHeader* payload) -{ - char dirPath[kMaxDataLength]; - strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength); - - DIR *dp = opendir(dirPath); - - if (dp == nullptr) { - warnx("FTP: can't open path '%s'", dirPath); - return kErrFailErrno; - } - -#ifdef MAVLINK_FTP_DEBUG - warnx("FTP: list %s offset %d", dirPath, payload->offset); -#endif - - ErrorCode errorCode = kErrNone; - struct dirent entry, *result = nullptr; - unsigned offset = 0; - - // move to the requested offset - seekdir(dp, payload->offset); - - for (;;) { - // read the directory entry - if (readdir_r(dp, &entry, &result)) { - warnx("FTP: list %s readdir_r failure\n", dirPath); - errorCode = kErrFailErrno; - break; - } - - // no more entries? - if (result == nullptr) { - if (payload->offset != 0 && offset == 0) { - // User is requesting subsequent dir entries but there were none. This means the user asked - // to seek past EOF. - errorCode = kErrEOF; - } - // Otherwise we are just at the last directory entry, so we leave the errorCode at kErrorNone to signal that - break; - } - - uint32_t fileSize = 0; - char buf[256]; - char direntType; - - // Determine the directory entry type - switch (entry.d_type) { - case DTYPE_FILE: - // For files we get the file size as well - direntType = kDirentFile; - snprintf(buf, sizeof(buf), "%s/%s", dirPath, entry.d_name); - struct stat st; - if (stat(buf, &st) == 0) { - fileSize = st.st_size; - } - break; - case DTYPE_DIRECTORY: - if (strcmp(entry.d_name, ".") == 0 || strcmp(entry.d_name, "..") == 0) { - // Don't bother sending these back - direntType = kDirentSkip; - } else { - direntType = kDirentDir; - } - break; - default: - // We only send back file and diretory entries, skip everything else - direntType = kDirentSkip; - } - - if (direntType == kDirentSkip) { - // Skip send only dirent identifier - buf[0] = '\0'; - } else if (direntType == kDirentFile) { - // Files send filename and file length - snprintf(buf, sizeof(buf), "%s\t%d", entry.d_name, fileSize); - } else { - // Everything else just sends name - strncpy(buf, entry.d_name, sizeof(buf)); - buf[sizeof(buf)-1] = 0; - } - size_t nameLen = strlen(buf); - - // Do we have room for the name, the one char directory identifier and the null terminator? - if ((offset + nameLen + 2) > kMaxDataLength) { - break; - } - - // Move the data into the buffer - payload->data[offset++] = direntType; - strcpy((char *)&payload->data[offset], buf); -#ifdef MAVLINK_FTP_DEBUG - printf("FTP: list %s %s\n", dirPath, (char *)&payload->data[offset-1]); -#endif - offset += nameLen + 1; - } - - closedir(dp); - payload->size = offset; - - return errorCode; -} - -/// @brief Responds to an Open command -MavlinkFTP::ErrorCode -MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag) -{ - int session_index = _find_unused_session(); - if (session_index < 0) { - warnx("FTP: Open failed - out of sessions\n"); - return kErrNoSessionsAvailable; - } - - char *filename = _data_as_cstring(payload); - - uint32_t fileSize = 0; - struct stat st; - if (stat(filename, &st) != 0) { - // fail only if requested open for read - if (oflag & O_RDONLY) - return kErrFailErrno; - else - st.st_size = 0; - } - fileSize = st.st_size; - - int fd = ::open(filename, oflag); - if (fd < 0) { - return kErrFailErrno; - } - _session_fds[session_index] = fd; - - payload->session = session_index; - payload->size = sizeof(uint32_t); - *((uint32_t*)payload->data) = fileSize; - - return kErrNone; -} - -/// @brief Responds to a Read command -MavlinkFTP::ErrorCode -MavlinkFTP::_workRead(PayloadHeader* payload) -{ - int session_index = payload->session; - - if (!_valid_session(session_index)) { - return kErrInvalidSession; - } - - // Seek to the specified position -#ifdef MAVLINK_FTP_DEBUG - warnx("seek %d", payload->offset); -#endif - if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) { - // Unable to see to the specified location - warnx("seek fail"); - return kErrEOF; - } - - int bytes_read = ::read(_session_fds[session_index], &payload->data[0], kMaxDataLength); - if (bytes_read < 0) { - // Negative return indicates error other than eof - warnx("read fail %d", bytes_read); - return kErrFailErrno; - } - - payload->size = bytes_read; - - return kErrNone; -} - -/// @brief Responds to a Write command -MavlinkFTP::ErrorCode -MavlinkFTP::_workWrite(PayloadHeader* payload) -{ - int session_index = payload->session; - - if (!_valid_session(session_index)) { - return kErrInvalidSession; - } - - // Seek to the specified position -#ifdef MAVLINK_FTP_DEBUG - warnx("seek %d", payload->offset); -#endif - if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) { - // Unable to see to the specified location - warnx("seek fail"); - return kErrFailErrno; - } - - int bytes_written = ::write(_session_fds[session_index], &payload->data[0], payload->size); - if (bytes_written < 0) { - // Negative return indicates error other than eof - warnx("write fail %d", bytes_written); - return kErrFailErrno; - } - - payload->size = sizeof(uint32_t); - *((uint32_t*)payload->data) = bytes_written; - - return kErrNone; -} - -/// @brief Responds to a RemoveFile command -MavlinkFTP::ErrorCode -MavlinkFTP::_workRemoveFile(PayloadHeader* payload) -{ - char file[kMaxDataLength]; - strncpy(file, _data_as_cstring(payload), kMaxDataLength); - - if (unlink(file) == 0) { - payload->size = 0; - return kErrNone; - } else { - return kErrFailErrno; - } -} - -/// @brief Responds to a TruncateFile command -MavlinkFTP::ErrorCode -MavlinkFTP::_workTruncateFile(PayloadHeader* payload) -{ - char file[kMaxDataLength]; - const char temp_file[] = "/fs/microsd/.trunc.tmp"; - strncpy(file, _data_as_cstring(payload), kMaxDataLength); - payload->size = 0; - - // emulate truncate(file, payload->offset) by - // copying to temp and overwrite with O_TRUNC flag. - - struct stat st; - if (stat(file, &st) != 0) { - return kErrFailErrno; - } - - if (!S_ISREG(st.st_mode)) { - errno = EISDIR; - return kErrFailErrno; - } - - // check perms allow us to write (not romfs) - if (!(st.st_mode & (S_IWUSR | S_IWGRP | S_IWOTH))) { - errno = EROFS; - return kErrFailErrno; - } - - if (payload->offset == (unsigned)st.st_size) { - // nothing to do - return kErrNone; - } - else if (payload->offset == 0) { - // 1: truncate all data - int fd = ::open(file, O_TRUNC | O_WRONLY); - if (fd < 0) { - return kErrFailErrno; - } - - ::close(fd); - return kErrNone; - } - else if (payload->offset > (unsigned)st.st_size) { - // 2: extend file - int fd = ::open(file, O_WRONLY); - if (fd < 0) { - return kErrFailErrno; - } - - if (lseek(fd, payload->offset - 1, SEEK_SET) < 0) { - ::close(fd); - return kErrFailErrno; - } - - bool ok = 1 == ::write(fd, "", 1); - ::close(fd); - - return (ok)? kErrNone : kErrFailErrno; - } - else { - // 3: truncate - if (_copy_file(file, temp_file, payload->offset) != 0) { - return kErrFailErrno; - } - if (_copy_file(temp_file, file, payload->offset) != 0) { - return kErrFailErrno; - } - if (::unlink(temp_file) != 0) { - return kErrFailErrno; - } - - return kErrNone; - } -} - -/// @brief Responds to a Terminate command -MavlinkFTP::ErrorCode -MavlinkFTP::_workTerminate(PayloadHeader* payload) -{ - if (!_valid_session(payload->session)) { - return kErrInvalidSession; - } - - ::close(_session_fds[payload->session]); - _session_fds[payload->session] = -1; - - payload->size = 0; - - return kErrNone; -} - -/// @brief Responds to a Reset command -MavlinkFTP::ErrorCode -MavlinkFTP::_workReset(PayloadHeader* payload) -{ - for (size_t i=0; isize = 0; - - return kErrNone; -} - -/// @brief Responds to a Rename command -MavlinkFTP::ErrorCode -MavlinkFTP::_workRename(PayloadHeader* payload) -{ - char oldpath[kMaxDataLength]; - char newpath[kMaxDataLength]; - - char *ptr = _data_as_cstring(payload); - size_t oldpath_sz = strlen(ptr); - - if (oldpath_sz == payload->size) { - // no newpath - errno = EINVAL; - return kErrFailErrno; - } - - strncpy(oldpath, ptr, kMaxDataLength); - strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength); - - if (rename(oldpath, newpath) == 0) { - payload->size = 0; - return kErrNone; - } else { - return kErrFailErrno; - } -} - -/// @brief Responds to a RemoveDirectory command -MavlinkFTP::ErrorCode -MavlinkFTP::_workRemoveDirectory(PayloadHeader* payload) -{ - char dir[kMaxDataLength]; - strncpy(dir, _data_as_cstring(payload), kMaxDataLength); - - if (rmdir(dir) == 0) { - payload->size = 0; - return kErrNone; - } else { - return kErrFailErrno; - } -} - -/// @brief Responds to a CreateDirectory command -MavlinkFTP::ErrorCode -MavlinkFTP::_workCreateDirectory(PayloadHeader* payload) -{ - char dir[kMaxDataLength]; - strncpy(dir, _data_as_cstring(payload), kMaxDataLength); - - if (mkdir(dir, S_IRWXU | S_IRWXG | S_IRWXO) == 0) { - payload->size = 0; - return kErrNone; - } else { - return kErrFailErrno; - } -} - -/// @brief Responds to a CalcFileCRC32 command -MavlinkFTP::ErrorCode -MavlinkFTP::_workCalcFileCRC32(PayloadHeader* payload) -{ - char file_buf[256]; - uint32_t checksum = 0; - ssize_t bytes_read; - strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength); - - int fd = ::open(file_buf, O_RDONLY); - if (fd < 0) { - return kErrFailErrno; - } - - do { - bytes_read = ::read(fd, file_buf, sizeof(file_buf)); - if (bytes_read < 0) { - int r_errno = errno; - ::close(fd); - errno = r_errno; - return kErrFailErrno; - } - - checksum = crc32part((uint8_t*)file_buf, bytes_read, checksum); - } while (bytes_read == sizeof(file_buf)); - - ::close(fd); - - payload->size = sizeof(uint32_t); - *((uint32_t*)payload->data) = checksum; - return kErrNone; -} - -/// @brief Returns true if the specified session is a valid open session -bool -MavlinkFTP::_valid_session(unsigned index) -{ - if ((index >= kMaxSession) || (_session_fds[index] < 0)) { - return false; - } - return true; -} - -/// @brief Returns an unused session index -int -MavlinkFTP::_find_unused_session(void) -{ - for (size_t i=0; isize < kMaxDataLength) { - payload->data[payload->size] = '\0'; - } else { - payload->data[kMaxDataLength - 1] = '\0'; - } - - // and return data - return (char *)&(payload->data[0]); -} - -/// @brief Returns a unused Request entry. NULL if none available. -MavlinkFTP::Request * -MavlinkFTP::_get_request(void) -{ - _lock_request_queue(); - Request* req = reinterpret_cast(dq_remfirst(&_request_queue)); - _unlock_request_queue(); - return req; -} - -/// @brief Locks a semaphore to provide exclusive access to the request queue -void -MavlinkFTP::_lock_request_queue(void) -{ - do {} - while (sem_wait(&_request_queue_sem) != 0); -} - -/// @brief Unlocks the semaphore providing exclusive access to the request queue -void -MavlinkFTP::_unlock_request_queue(void) -{ - sem_post(&_request_queue_sem); -} - -/// @brief Returns a no longer needed request to the queue -void -MavlinkFTP::_return_request(Request *req) -{ - _lock_request_queue(); - dq_addlast(&req->work.dq, &_request_queue); - _unlock_request_queue(); -} - -/// @brief Copy file (with limited space) -int -MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length) -{ - char buff[512]; - int src_fd = -1, dst_fd = -1; - int op_errno = 0; - - src_fd = ::open(src_path, O_RDONLY); - if (src_fd < 0) { - return -1; - } - - dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY); - if (dst_fd < 0) { - op_errno = errno; - ::close(src_fd); - errno = op_errno; - return -1; - } - - while (length > 0) { - ssize_t bytes_read, bytes_written; - size_t blen = (length > sizeof(buff))? sizeof(buff) : length; - - bytes_read = ::read(src_fd, buff, blen); - if (bytes_read == 0) { - // EOF - break; - } - else if (bytes_read < 0) { - warnx("cp: read"); - op_errno = errno; - break; - } - - bytes_written = ::write(dst_fd, buff, bytes_read); - if (bytes_written != bytes_read) { - warnx("cp: short write"); - op_errno = errno; - break; - } - - length -= bytes_written; - } - - ::close(src_fd); - ::close(dst_fd); - - errno = op_errno; - return (length > 0)? -1 : 0; -} diff --git a/src/modules/mavlink/mavlink_receiver_posix.cpp b/src/modules/mavlink/mavlink_receiver.cpp similarity index 99% rename from src/modules/mavlink/mavlink_receiver_posix.cpp rename to src/modules/mavlink/mavlink_receiver.cpp index bfe7a4552c..03ad2eca15 100644 --- a/src/modules/mavlink/mavlink_receiver_posix.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -41,7 +41,12 @@ */ /* XXX trim includes */ +#ifdef __PX4_NUTTX +#include +#include +#else #include +#endif #include #include #include @@ -1495,14 +1500,14 @@ MavlinkReceiver::receive_thread(void *arg) sprintf(thread_name, "mavlink_rcv_if%d", _mavlink->get_instance_id()); prctl(PR_SET_NAME, thread_name, getpid()); - px4_pollfd_struct_t fds[1]; + struct pollfd fds[1]; fds[0].fd = uart_fd; fds[0].events = POLLIN; ssize_t nread = 0; while (!_mavlink->_task_should_exit) { - if (px4_poll(fds, 1, timeout) > 0) { + if (poll(fds, 1, timeout) > 0) { /* non-blocking read. read may return negative values */ if ((nread = ::read(uart_fd, buf, sizeof(buf))) < (ssize_t)sizeof(buf)) { diff --git a/src/modules/mavlink/mavlink_receiver_nuttx.cpp b/src/modules/mavlink/mavlink_receiver_nuttx.cpp deleted file mode 100644 index faede15cb9..0000000000 --- a/src/modules/mavlink/mavlink_receiver_nuttx.cpp +++ /dev/null @@ -1,1590 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mavlink_receiver.cpp - * MAVLink protocol message receive and dispatch - * - * @author Lorenz Meier - * @author Anton Babushkin - * @author Thomas Gubler - */ - -/* XXX trim includes */ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - -#include -#include -#include -#include -#include -#include -#include - -__BEGIN_DECLS - -#include "mavlink_bridge_header.h" -#include "mavlink_receiver.h" -#include "mavlink_main.h" - -__END_DECLS - -static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f; - -MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : - _mavlink(parent), - status{}, - hil_local_pos{}, - hil_land_detector{}, - _control_mode{}, - _global_pos_pub(-1), - _local_pos_pub(-1), - _attitude_pub(-1), - _gps_pub(-1), - _sensors_pub(-1), - _gyro_pub(-1), - _accel_pub(-1), - _mag_pub(-1), - _baro_pub(-1), - _airspeed_pub(-1), - _battery_pub(-1), - _cmd_pub(-1), - _flow_pub(-1), - _range_pub(-1), - _offboard_control_mode_pub(-1), - _actuator_controls_pub(-1), - _global_vel_sp_pub(-1), - _att_sp_pub(-1), - _rates_sp_pub(-1), - _force_sp_pub(-1), - _pos_sp_triplet_pub(-1), - _vicon_position_pub(-1), - _vision_position_pub(-1), - _telemetry_status_pub(-1), - _rc_pub(-1), - _manual_pub(-1), - _land_detector_pub(-1), - _time_offset_pub(-1), - _control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))), - _hil_frames(0), - _old_timestamp(0), - _hil_local_proj_inited(0), - _hil_local_alt0(0.0f), - _hil_local_proj_ref{}, - _offboard_control_mode{}, - _rates_sp{}, - _time_offset_avg_alpha(0.6), - _time_offset(0) -{ - - // make sure the FTP server is started - (void)MavlinkFTP::get_server(); -} - -MavlinkReceiver::~MavlinkReceiver() -{ -} - -void -MavlinkReceiver::handle_message(mavlink_message_t *msg) -{ - switch (msg->msgid) { - case MAVLINK_MSG_ID_COMMAND_LONG: - handle_message_command_long(msg); - break; - - case MAVLINK_MSG_ID_COMMAND_INT: - handle_message_command_int(msg); - break; - - case MAVLINK_MSG_ID_OPTICAL_FLOW_RAD: - handle_message_optical_flow_rad(msg); - break; - - case MAVLINK_MSG_ID_PING: - handle_message_ping(msg); - break; - - case MAVLINK_MSG_ID_SET_MODE: - handle_message_set_mode(msg); - break; - - case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE: - handle_message_vicon_position_estimate(msg); - break; - - case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: - handle_message_set_position_target_local_ned(msg); - break; - - case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: - handle_message_set_attitude_target(msg); - break; - - case MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET: - handle_message_set_actuator_control_target(msg); - break; - - case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE: - handle_message_vision_position_estimate(msg); - break; - - case MAVLINK_MSG_ID_RADIO_STATUS: - handle_message_radio_status(msg); - break; - - case MAVLINK_MSG_ID_MANUAL_CONTROL: - handle_message_manual_control(msg); - break; - - case MAVLINK_MSG_ID_HEARTBEAT: - handle_message_heartbeat(msg); - break; - - case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: - handle_message_request_data_stream(msg); - break; - - case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL: - MavlinkFTP::get_server()->handle_message(_mavlink, msg); - break; - - case MAVLINK_MSG_ID_SYSTEM_TIME: - handle_message_system_time(msg); - break; - - case MAVLINK_MSG_ID_TIMESYNC: - handle_message_timesync(msg); - break; - - default: - break; - } - - /* - * Only decode hil messages in HIL mode. - * - * The HIL mode is enabled by the HIL bit flag - * in the system mode. Either send a set mode - * COMMAND_LONG message or a SET_MODE message - * - * Accept HIL GPS messages if use_hil_gps flag is true. - * This allows to provide fake gps measurements to the system. - */ - if (_mavlink->get_hil_enabled()) { - switch (msg->msgid) { - case MAVLINK_MSG_ID_HIL_SENSOR: - handle_message_hil_sensor(msg); - break; - - case MAVLINK_MSG_ID_HIL_STATE_QUATERNION: - handle_message_hil_state_quaternion(msg); - break; - - case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW: - handle_message_hil_optical_flow(msg); - break; - - default: - break; - } - } - - - if (_mavlink->get_hil_enabled() || (_mavlink->get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) { - switch (msg->msgid) { - case MAVLINK_MSG_ID_HIL_GPS: - handle_message_hil_gps(msg); - break; - - default: - break; - } - - } - - /* If we've received a valid message, mark the flag indicating so. - This is used in the '-w' command-line flag. */ - _mavlink->set_has_received_messages(true); -} - -void -MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) -{ - /* command */ - mavlink_command_long_t cmd_mavlink; - mavlink_msg_command_long_decode(msg, &cmd_mavlink); - - if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) - || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { - //check for MAVLINK terminate command - if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { - /* This is the link shutdown command, terminate mavlink */ - warnx("terminated by remote"); - fflush(stdout); - usleep(50000); - - /* terminate other threads and this thread */ - _mavlink->_task_should_exit = true; - - } else { - - if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) { - warnx("ignoring CMD with same SYS/COMP (%d/%d) ID", - mavlink_system.sysid, mavlink_system.compid); - return; - } - - struct vehicle_command_s vcmd; - memset(&vcmd, 0, sizeof(vcmd)); - - /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ - vcmd.param1 = cmd_mavlink.param1; - vcmd.param2 = cmd_mavlink.param2; - vcmd.param3 = cmd_mavlink.param3; - vcmd.param4 = cmd_mavlink.param4; - vcmd.param5 = cmd_mavlink.param5; - vcmd.param6 = cmd_mavlink.param6; - vcmd.param7 = cmd_mavlink.param7; - // XXX do proper translation - vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command; - vcmd.target_system = cmd_mavlink.target_system; - vcmd.target_component = cmd_mavlink.target_component; - vcmd.source_system = msg->sysid; - vcmd.source_component = msg->compid; - vcmd.confirmation = cmd_mavlink.confirmation; - - if (_cmd_pub < 0) { - _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); - - } else { - orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd); - } - } - } -} - -void -MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg) -{ - /* command */ - mavlink_command_int_t cmd_mavlink; - mavlink_msg_command_int_decode(msg, &cmd_mavlink); - - if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) - || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { - //check for MAVLINK terminate command - if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { - /* This is the link shutdown command, terminate mavlink */ - warnx("terminated by remote"); - fflush(stdout); - usleep(50000); - - /* terminate other threads and this thread */ - _mavlink->_task_should_exit = true; - - } else { - - if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) { - warnx("ignoring CMD with same SYS/COMP (%d/%d) ID", - mavlink_system.sysid, mavlink_system.compid); - return; - } - - struct vehicle_command_s vcmd; - memset(&vcmd, 0, sizeof(vcmd)); - - /* Copy the content of mavlink_command_int_t cmd_mavlink into command_t cmd */ - vcmd.param1 = cmd_mavlink.param1; - vcmd.param2 = cmd_mavlink.param2; - vcmd.param3 = cmd_mavlink.param3; - vcmd.param4 = cmd_mavlink.param4; - /* these are coordinates as 1e7 scaled integers to work around the 32 bit floating point limits */ - vcmd.param5 = ((double)cmd_mavlink.x) / 1e7; - vcmd.param6 = ((double)cmd_mavlink.y) / 1e7; - vcmd.param7 = cmd_mavlink.z; - // XXX do proper translation - vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command; - vcmd.target_system = cmd_mavlink.target_system; - vcmd.target_component = cmd_mavlink.target_component; - vcmd.source_system = msg->sysid; - vcmd.source_component = msg->compid; - - if (_cmd_pub < 0) { - _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); - - } else { - orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd); - } - } - } -} - -void -MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) -{ - /* optical flow */ - mavlink_optical_flow_rad_t flow; - mavlink_msg_optical_flow_rad_decode(msg, &flow); - - enum Rotation flow_rot; - param_get(param_find("SENS_FLOW_ROT"),&flow_rot); - - struct optical_flow_s f; - memset(&f, 0, sizeof(f)); - - f.timestamp = flow.time_usec; - f.integration_timespan = flow.integration_time_us; - f.pixel_flow_x_integral = flow.integrated_x; - f.pixel_flow_y_integral = flow.integrated_y; - f.gyro_x_rate_integral = flow.integrated_xgyro; - f.gyro_y_rate_integral = flow.integrated_ygyro; - f.gyro_z_rate_integral = flow.integrated_zgyro; - f.time_since_last_sonar_update = flow.time_delta_distance_us; - f.ground_distance_m = flow.distance; - f.quality = flow.quality; - f.sensor_id = flow.sensor_id; - f.gyro_temperature = flow.temperature; - - /* rotate measurements according to parameter */ - float zeroval = 0.0f; - rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zeroval); - - if (_flow_pub < 0) { - _flow_pub = orb_advertise(ORB_ID(optical_flow), &f); - - } else { - orb_publish(ORB_ID(optical_flow), _flow_pub, &f); - } -} - -void -MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) -{ - /* optical flow */ - mavlink_hil_optical_flow_t flow; - mavlink_msg_hil_optical_flow_decode(msg, &flow); - - struct optical_flow_s f; - memset(&f, 0, sizeof(f)); - - f.timestamp = hrt_absolute_time(); // XXX we rely on the system time for now and not flow.time_usec; - f.integration_timespan = flow.integration_time_us; - f.pixel_flow_x_integral = flow.integrated_x; - f.pixel_flow_y_integral = flow.integrated_y; - f.gyro_x_rate_integral = flow.integrated_xgyro; - f.gyro_y_rate_integral = flow.integrated_ygyro; - f.gyro_z_rate_integral = flow.integrated_zgyro; - f.time_since_last_sonar_update = flow.time_delta_distance_us; - f.ground_distance_m = flow.distance; - f.quality = flow.quality; - f.sensor_id = flow.sensor_id; - f.gyro_temperature = flow.temperature; - - if (_flow_pub < 0) { - _flow_pub = orb_advertise(ORB_ID(optical_flow), &f); - - } else { - orb_publish(ORB_ID(optical_flow), _flow_pub, &f); - } - - /* Use distance value for range finder report */ - struct range_finder_report r; - memset(&r, 0, sizeof(r)); - - r.timestamp = hrt_absolute_time(); - r.error_count = 0; - r.type = RANGE_FINDER_TYPE_LASER; - r.distance = flow.distance; - r.minimum_distance = 0.0f; - r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable - r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance); - - if (_range_pub < 0) { - _range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r); - } else { - orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r); - } -} - -void -MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg) -{ - mavlink_set_mode_t new_mode; - mavlink_msg_set_mode_decode(msg, &new_mode); - - struct vehicle_command_s vcmd; - memset(&vcmd, 0, sizeof(vcmd)); - - union px4_custom_mode custom_mode; - custom_mode.data = new_mode.custom_mode; - /* copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */ - vcmd.param1 = new_mode.base_mode; - vcmd.param2 = custom_mode.main_mode; - vcmd.param3 = 0; - vcmd.param4 = 0; - vcmd.param5 = 0; - vcmd.param6 = 0; - vcmd.param7 = 0; - vcmd.command = VEHICLE_CMD_DO_SET_MODE; - vcmd.target_system = new_mode.target_system; - vcmd.target_component = MAV_COMP_ID_ALL; - vcmd.source_system = msg->sysid; - vcmd.source_component = msg->compid; - vcmd.confirmation = 1; - - if (_cmd_pub < 0) { - _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); - - } else { - orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd); - } -} - -void -MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg) -{ - mavlink_vicon_position_estimate_t pos; - mavlink_msg_vicon_position_estimate_decode(msg, &pos); - - struct vehicle_vicon_position_s vicon_position; - memset(&vicon_position, 0, sizeof(vicon_position)); - - vicon_position.timestamp = hrt_absolute_time(); - vicon_position.x = pos.x; - vicon_position.y = pos.y; - vicon_position.z = pos.z; - vicon_position.roll = pos.roll; - vicon_position.pitch = pos.pitch; - vicon_position.yaw = pos.yaw; - - if (_vicon_position_pub < 0) { - _vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position); - - } else { - orb_publish(ORB_ID(vehicle_vicon_position), _vicon_position_pub, &vicon_position); - } -} - -void -MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t *msg) -{ - mavlink_set_position_target_local_ned_t set_position_target_local_ned; - mavlink_msg_set_position_target_local_ned_decode(msg, &set_position_target_local_ned); - - struct offboard_control_mode_s offboard_control_mode; - memset(&offboard_control_mode, 0, sizeof(offboard_control_mode));//XXX breaks compatibility with multiple setpoints - - /* Only accept messages which are intended for this system */ - if ((mavlink_system.sysid == set_position_target_local_ned.target_system || - set_position_target_local_ned.target_system == 0) && - (mavlink_system.compid == set_position_target_local_ned.target_component || - set_position_target_local_ned.target_component == 0)) { - - /* convert mavlink type (local, NED) to uORB offboard control struct */ - offboard_control_mode.ignore_position = (bool)(set_position_target_local_ned.type_mask & 0x7); - offboard_control_mode.ignore_velocity = (bool)(set_position_target_local_ned.type_mask & 0x38); - offboard_control_mode.ignore_acceleration_force = (bool)(set_position_target_local_ned.type_mask & 0x1C0); - bool is_force_sp = (bool)(set_position_target_local_ned.type_mask & (1 << 9)); - /* yaw ignore flag mapps to ignore_attitude */ - offboard_control_mode.ignore_attitude = (bool)(set_position_target_local_ned.type_mask & 0x400); - /* yawrate ignore flag mapps to ignore_bodyrate */ - offboard_control_mode.ignore_bodyrate = (bool)(set_position_target_local_ned.type_mask & 0x800); - - offboard_control_mode.timestamp = hrt_absolute_time(); - - if (_offboard_control_mode_pub < 0) { - _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); - - } else { - orb_publish(ORB_ID(offboard_control_mode), _offboard_control_mode_pub, &offboard_control_mode); - } - - /* If we are in offboard control mode and offboard control loop through is enabled - * also publish the setpoint topic which is read by the controller */ - if (_mavlink->get_forward_externalsp()) { - bool updated; - orb_check(_control_mode_sub, &updated); - if (updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - } - if (_control_mode.flag_control_offboard_enabled) { - if (is_force_sp && offboard_control_mode.ignore_position && - offboard_control_mode.ignore_velocity) { - /* The offboard setpoint is a force setpoint only, directly writing to the force - * setpoint topic and not publishing the setpoint triplet topic */ - struct vehicle_force_setpoint_s force_sp; - force_sp.x = set_position_target_local_ned.afx; - force_sp.y = set_position_target_local_ned.afy; - force_sp.z = set_position_target_local_ned.afz; - //XXX: yaw - if (_force_sp_pub < 0) { - _force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp); - } else { - orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp); - } - } else { - /* It's not a pure force setpoint: publish to setpoint triplet topic */ - struct position_setpoint_triplet_s pos_sp_triplet; - pos_sp_triplet.previous.valid = false; - pos_sp_triplet.next.valid = false; - pos_sp_triplet.current.valid = true; - pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_POSITION; //XXX support others - - /* set the local pos values */ - if (!offboard_control_mode.ignore_position) { - pos_sp_triplet.current.position_valid = true; - pos_sp_triplet.current.x = set_position_target_local_ned.x; - pos_sp_triplet.current.y = set_position_target_local_ned.y; - pos_sp_triplet.current.z = set_position_target_local_ned.z; - } else { - pos_sp_triplet.current.position_valid = false; - } - - /* set the local vel values */ - if (!offboard_control_mode.ignore_velocity) { - pos_sp_triplet.current.velocity_valid = true; - pos_sp_triplet.current.vx = set_position_target_local_ned.vx; - pos_sp_triplet.current.vy = set_position_target_local_ned.vy; - pos_sp_triplet.current.vz = set_position_target_local_ned.vz; - } else { - pos_sp_triplet.current.velocity_valid = false; - } - - /* set the local acceleration values if the setpoint type is 'local pos' and none - * of the accelerations fields is set to 'ignore' */ - if (!offboard_control_mode.ignore_acceleration_force) { - pos_sp_triplet.current.acceleration_valid = true; - pos_sp_triplet.current.a_x = set_position_target_local_ned.afx; - pos_sp_triplet.current.a_y = set_position_target_local_ned.afy; - pos_sp_triplet.current.a_z = set_position_target_local_ned.afz; - pos_sp_triplet.current.acceleration_is_force = - is_force_sp; - - } else { - pos_sp_triplet.current.acceleration_valid = false; - } - - /* set the yaw sp value */ - if (!offboard_control_mode.ignore_attitude) { - pos_sp_triplet.current.yaw_valid = true; - pos_sp_triplet.current.yaw = set_position_target_local_ned.yaw; - - } else { - pos_sp_triplet.current.yaw_valid = false; - } - - /* set the yawrate sp value */ - if (!offboard_control_mode.ignore_bodyrate) { - pos_sp_triplet.current.yawspeed_valid = true; - pos_sp_triplet.current.yawspeed = set_position_target_local_ned.yaw_rate; - - } else { - pos_sp_triplet.current.yawspeed_valid = false; - } - //XXX handle global pos setpoints (different MAV frames) - - - if (_pos_sp_triplet_pub < 0) { - _pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), - &pos_sp_triplet); - } else { - orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, - &pos_sp_triplet); - } - - } - - } - - } - } -} - -void -MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *msg) -{ - mavlink_set_actuator_control_target_t set_actuator_control_target; - mavlink_msg_set_actuator_control_target_decode(msg, &set_actuator_control_target); - - struct offboard_control_mode_s offboard_control_mode; - memset(&offboard_control_mode, 0, sizeof(offboard_control_mode));//XXX breaks compatibility with multiple setpoints - - struct actuator_controls_s actuator_controls; - memset(&actuator_controls, 0, sizeof(actuator_controls));//XXX breaks compatibility with multiple setpoints - - if ((mavlink_system.sysid == set_actuator_control_target.target_system || - set_actuator_control_target.target_system == 0) && - (mavlink_system.compid == set_actuator_control_target.target_component || - set_actuator_control_target.target_component == 0)) { - - /* ignore all since we are setting raw actuators here */ - offboard_control_mode.ignore_thrust = true; - offboard_control_mode.ignore_attitude = true; - offboard_control_mode.ignore_bodyrate = true; - offboard_control_mode.ignore_position = true; - offboard_control_mode.ignore_velocity = true; - offboard_control_mode.ignore_acceleration_force = true; - - offboard_control_mode.timestamp = hrt_absolute_time(); - - if (_offboard_control_mode_pub < 0) { - _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); - } else { - orb_publish(ORB_ID(offboard_control_mode), _offboard_control_mode_pub, &offboard_control_mode); - } - - - /* If we are in offboard control mode, publish the actuator controls */ - bool updated; - orb_check(_control_mode_sub, &updated); - if (updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - } - - if (_control_mode.flag_control_offboard_enabled) { - - actuator_controls.timestamp = hrt_absolute_time(); - - /* Set duty cycles for the servos in actuator_controls_0 */ - for(size_t i = 0; i < 8; i++) { - actuator_controls.control[i] = set_actuator_control_target.controls[i]; - } - - if (_actuator_controls_pub < 0) { - _actuator_controls_pub = orb_advertise(ORB_ID(actuator_controls_0), &actuator_controls); - } else { - orb_publish(ORB_ID(actuator_controls_0), _actuator_controls_pub, &actuator_controls); - } - } - } - -} - -void -MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg) -{ - mavlink_vision_position_estimate_t pos; - mavlink_msg_vision_position_estimate_decode(msg, &pos); - - struct vision_position_estimate vision_position; - memset(&vision_position, 0, sizeof(vision_position)); - - // Use the component ID to identify the vision sensor - vision_position.id = msg->compid; - - vision_position.timestamp_boot = hrt_absolute_time(); // Monotonic time - vision_position.timestamp_computer = sync_stamp(pos.usec); // Synced time - vision_position.x = pos.x; - vision_position.y = pos.y; - vision_position.z = pos.z; - - // XXX fix this - vision_position.vx = 0.0f; - vision_position.vy = 0.0f; - vision_position.vz = 0.0f; - - math::Quaternion q; - q.from_euler(pos.roll, pos.pitch, pos.yaw); - - vision_position.q[0] = q(0); - vision_position.q[1] = q(1); - vision_position.q[2] = q(2); - vision_position.q[3] = q(3); - - if (_vision_position_pub < 0) { - _vision_position_pub = orb_advertise(ORB_ID(vision_position_estimate), &vision_position); - - } else { - orb_publish(ORB_ID(vision_position_estimate), _vision_position_pub, &vision_position); - } -} - -void -MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) -{ - mavlink_set_attitude_target_t set_attitude_target; - mavlink_msg_set_attitude_target_decode(msg, &set_attitude_target); - - /* Only accept messages which are intended for this system */ - if ((mavlink_system.sysid == set_attitude_target.target_system || - set_attitude_target.target_system == 0) && - (mavlink_system.compid == set_attitude_target.target_component || - set_attitude_target.target_component == 0)) { - - /* set correct ignore flags for thrust field: copy from mavlink message */ - _offboard_control_mode.ignore_thrust = (bool)(set_attitude_target.type_mask & (1 << 6)); - - /* - * The tricky part in parsing this message is that the offboard sender *can* set attitude and thrust - * using different messages. Eg.: First send set_attitude_target containing the attitude and ignore - * bits set for everything else and then send set_attitude_target containing the thrust and ignore bits - * set for everything else. - */ - - /* - * if attitude or body rate have been used (not ignored) previously and this message only sends - * throttle and has the ignore bits set for attitude and rates don't change the flags for attitude and - * body rates to keep the controllers running - */ - bool ignore_bodyrate = (bool)(set_attitude_target.type_mask & 0x7); - bool ignore_attitude = (bool)(set_attitude_target.type_mask & (1 << 7)); - - if (ignore_bodyrate && ignore_attitude && !_offboard_control_mode.ignore_thrust) { - /* Message want's us to ignore everything except thrust: only ignore if previously ignored */ - _offboard_control_mode.ignore_bodyrate = ignore_bodyrate && _offboard_control_mode.ignore_bodyrate; - _offboard_control_mode.ignore_attitude = ignore_attitude && _offboard_control_mode.ignore_attitude; - } else { - _offboard_control_mode.ignore_bodyrate = ignore_bodyrate; - _offboard_control_mode.ignore_attitude = ignore_attitude; - } - - _offboard_control_mode.ignore_position = true; - _offboard_control_mode.ignore_velocity = true; - _offboard_control_mode.ignore_acceleration_force = true; - - _offboard_control_mode.timestamp = hrt_absolute_time(); - - if (_offboard_control_mode_pub < 0) { - _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &_offboard_control_mode); - - } else { - orb_publish(ORB_ID(offboard_control_mode), _offboard_control_mode_pub, &_offboard_control_mode); - } - - /* If we are in offboard control mode and offboard control loop through is enabled - * also publish the setpoint topic which is read by the controller */ - if (_mavlink->get_forward_externalsp()) { - bool updated; - orb_check(_control_mode_sub, &updated); - if (updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - } - - if (_control_mode.flag_control_offboard_enabled) { - - /* Publish attitude setpoint if attitude and thrust ignore bits are not set */ - if (!(_offboard_control_mode.ignore_attitude)) { - static struct vehicle_attitude_setpoint_s att_sp = {}; - att_sp.timestamp = hrt_absolute_time(); - mavlink_quaternion_to_euler(set_attitude_target.q, - &att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body); - mavlink_quaternion_to_dcm(set_attitude_target.q, (float(*)[3])att_sp.R_body); - att_sp.R_valid = true; - if (!_offboard_control_mode.ignore_thrust) { // dont't overwrite thrust if it's invalid - att_sp.thrust = set_attitude_target.thrust; - } - att_sp.yaw_sp_move_rate = 0.0; - memcpy(att_sp.q_d, set_attitude_target.q, sizeof(att_sp.q_d)); - att_sp.q_d_valid = true; - if (_att_sp_pub < 0) { - _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); - } else { - orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); - } - } - - /* Publish attitude rate setpoint if bodyrate and thrust ignore bits are not set */ - ///XXX add support for ignoring individual axes - if (!(_offboard_control_mode.ignore_bodyrate)) { - _rates_sp.timestamp = hrt_absolute_time(); - _rates_sp.roll = set_attitude_target.body_roll_rate; - _rates_sp.pitch = set_attitude_target.body_pitch_rate; - _rates_sp.yaw = set_attitude_target.body_yaw_rate; - if (!_offboard_control_mode.ignore_thrust) { // dont't overwrite thrust if it's invalid - _rates_sp.thrust = set_attitude_target.thrust; - } - - if (_att_sp_pub < 0) { - _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_rates_sp); - } else { - orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &_rates_sp); - } - } - } - - } - } -} - -void -MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) -{ - /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ - if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) { - mavlink_radio_status_t rstatus; - mavlink_msg_radio_status_decode(msg, &rstatus); - - struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); - - tstatus.timestamp = hrt_absolute_time(); - tstatus.telem_time = tstatus.timestamp; - /* tstatus.heartbeat_time is set by system heartbeats */ - tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; - tstatus.rssi = rstatus.rssi; - tstatus.remote_rssi = rstatus.remrssi; - tstatus.txbuf = rstatus.txbuf; - tstatus.noise = rstatus.noise; - tstatus.remote_noise = rstatus.remnoise; - tstatus.rxerrors = rstatus.rxerrors; - tstatus.fixed = rstatus.fixed; - tstatus.system_id = msg->sysid; - tstatus.component_id = msg->compid; - - if (_telemetry_status_pub < 0) { - _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); - - } else { - orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus); - } - } -} - -void -MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) -{ - mavlink_manual_control_t man; - mavlink_msg_manual_control_decode(msg, &man); - - struct manual_control_setpoint_s manual; - memset(&manual, 0, sizeof(manual)); - - manual.timestamp = hrt_absolute_time(); - manual.x = man.x / 1000.0f; - manual.y = man.y / 1000.0f; - manual.r = man.r / 1000.0f; - manual.z = man.z / 1000.0f; - - // warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z); - - if (_manual_pub < 0) { - _manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual); - - } else { - orb_publish(ORB_ID(manual_control_setpoint), _manual_pub, &manual); - } -} - -void -MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) -{ - /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ - if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) { - mavlink_heartbeat_t hb; - mavlink_msg_heartbeat_decode(msg, &hb); - - /* ignore own heartbeats, accept only heartbeats from GCS */ - if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) { - - struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); - - /* set heartbeat time and topic time and publish - - * the telem status also gets updated on telemetry events - */ - tstatus.timestamp = hrt_absolute_time(); - tstatus.heartbeat_time = tstatus.timestamp; - - if (_telemetry_status_pub < 0) { - _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); - - } else { - orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus); - } - } - } -} - -void -MavlinkReceiver::handle_message_ping(mavlink_message_t *msg) -{ - mavlink_ping_t ping; - mavlink_msg_ping_decode( msg, &ping); - if ((mavlink_system.sysid == ping.target_system) && - (mavlink_system.compid == ping.target_component)) { - mavlink_message_t msg_out; - mavlink_msg_ping_encode(_mavlink->get_system_id(), _mavlink->get_component_id(), &msg_out, &ping); - _mavlink->send_message(MAVLINK_MSG_ID_PING, &msg_out); - } -} - -void -MavlinkReceiver::handle_message_request_data_stream(mavlink_message_t *msg) -{ - mavlink_request_data_stream_t req; - mavlink_msg_request_data_stream_decode(msg, &req); - - if (req.target_system == mavlink_system.sysid && req.target_component == mavlink_system.compid && req.req_message_rate != 0) { - float rate = req.start_stop ? (1000.0f / req.req_message_rate) : 0.0f; - - MavlinkStream *stream; - LL_FOREACH(_mavlink->get_streams(), stream) { - if (req.req_stream_id == stream->get_id()) { - _mavlink->configure_stream_threadsafe(stream->get_name(), rate); - } - } - } -} - -void -MavlinkReceiver::handle_message_system_time(mavlink_message_t *msg) -{ - mavlink_system_time_t time; - mavlink_msg_system_time_decode(msg, &time); - - timespec tv; - clock_gettime(CLOCK_REALTIME, &tv); - - // date -d @1234567890: Sat Feb 14 02:31:30 MSK 2009 - bool onb_unix_valid = tv.tv_sec > PX4_EPOCH_SECS; - bool ofb_unix_valid = time.time_unix_usec > PX4_EPOCH_SECS * 1000ULL; - - if (!onb_unix_valid && ofb_unix_valid) { - tv.tv_sec = time.time_unix_usec / 1000000ULL; - tv.tv_nsec = (time.time_unix_usec % 1000000ULL) * 1000ULL; - if(clock_settime(CLOCK_REALTIME, &tv)) { - warn("failed setting clock"); - } - else { - warnx("[timesync] UTC time synced."); - } - } - -} - -void -MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg) -{ - mavlink_timesync_t tsync; - mavlink_msg_timesync_decode(msg, &tsync); - - struct time_offset_s tsync_offset; - memset(&tsync_offset, 0, sizeof(tsync_offset)); - - uint64_t now_ns = hrt_absolute_time() * 1000LL ; - - if (tsync.tc1 == 0) { - - mavlink_timesync_t rsync; // return timestamped sync message - - rsync.tc1 = now_ns; - rsync.ts1 = tsync.ts1; - - _mavlink->send_message(MAVLINK_MSG_ID_TIMESYNC, &rsync); - - return; - - } else if (tsync.tc1 > 0) { - - int64_t offset_ns = (tsync.ts1 + now_ns - tsync.tc1*2)/2 ; - int64_t dt = _time_offset - offset_ns; - - if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew - _time_offset = offset_ns; - warnx("[timesync] Hard setting offset."); - } else { - smooth_time_offset(offset_ns); - } - } - - tsync_offset.offset_ns = _time_offset ; - - if (_time_offset_pub < 0) { - _time_offset_pub = orb_advertise(ORB_ID(time_offset), &tsync_offset); - - } else { - orb_publish(ORB_ID(time_offset), _time_offset_pub, &tsync_offset); - } - -} - -void -MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) -{ - mavlink_hil_sensor_t imu; - mavlink_msg_hil_sensor_decode(msg, &imu); - - uint64_t timestamp = hrt_absolute_time(); - - /* airspeed */ - { - struct airspeed_s airspeed; - memset(&airspeed, 0, sizeof(airspeed)); - - float ias = calc_indicated_airspeed(imu.diff_pressure * 1e2f); - // XXX need to fix this - float tas = ias; - - airspeed.timestamp = timestamp; - airspeed.indicated_airspeed_m_s = ias; - airspeed.true_airspeed_m_s = tas; - - if (_airspeed_pub < 0) { - _airspeed_pub = orb_advertise(ORB_ID(airspeed), &airspeed); - - } else { - orb_publish(ORB_ID(airspeed), _airspeed_pub, &airspeed); - } - } - - /* gyro */ - { - struct gyro_report gyro; - memset(&gyro, 0, sizeof(gyro)); - - gyro.timestamp = timestamp; - gyro.x_raw = imu.xgyro * 1000.0f; - gyro.y_raw = imu.ygyro * 1000.0f; - gyro.z_raw = imu.zgyro * 1000.0f; - gyro.x = imu.xgyro; - gyro.y = imu.ygyro; - gyro.z = imu.zgyro; - gyro.temperature = imu.temperature; - - if (_gyro_pub < 0) { - _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro); - - } else { - orb_publish(ORB_ID(sensor_gyro), _gyro_pub, &gyro); - } - } - - /* accelerometer */ - { - struct accel_report accel; - memset(&accel, 0, sizeof(accel)); - - accel.timestamp = timestamp; - accel.x_raw = imu.xacc / mg2ms2; - accel.y_raw = imu.yacc / mg2ms2; - accel.z_raw = imu.zacc / mg2ms2; - accel.x = imu.xacc; - accel.y = imu.yacc; - accel.z = imu.zacc; - accel.temperature = imu.temperature; - - if (_accel_pub < 0) { - _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); - - } else { - orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel); - } - } - - /* magnetometer */ - { - struct mag_report mag; - memset(&mag, 0, sizeof(mag)); - - mag.timestamp = timestamp; - mag.x_raw = imu.xmag * 1000.0f; - mag.y_raw = imu.ymag * 1000.0f; - mag.z_raw = imu.zmag * 1000.0f; - mag.x = imu.xmag; - mag.y = imu.ymag; - mag.z = imu.zmag; - - if (_mag_pub < 0) { - /* publish to the first mag topic */ - _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag); - - } else { - orb_publish(ORB_ID(sensor_mag), _mag_pub, &mag); - } - } - - /* baro */ - { - struct baro_report baro; - memset(&baro, 0, sizeof(baro)); - - baro.timestamp = timestamp; - baro.pressure = imu.abs_pressure; - baro.altitude = imu.pressure_alt; - baro.temperature = imu.temperature; - - if (_baro_pub < 0) { - _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro); - - } else { - orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro); - } - } - - /* sensor combined */ - { - struct sensor_combined_s hil_sensors; - memset(&hil_sensors, 0, sizeof(hil_sensors)); - - hil_sensors.timestamp = timestamp; - - hil_sensors.gyro_raw[0] = imu.xgyro * 1000.0f; - hil_sensors.gyro_raw[1] = imu.ygyro * 1000.0f; - hil_sensors.gyro_raw[2] = imu.zgyro * 1000.0f; - hil_sensors.gyro_rad_s[0] = imu.xgyro; - hil_sensors.gyro_rad_s[1] = imu.ygyro; - hil_sensors.gyro_rad_s[2] = imu.zgyro; - - hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2; - hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2; - hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2; - hil_sensors.accelerometer_m_s2[0] = imu.xacc; - hil_sensors.accelerometer_m_s2[1] = imu.yacc; - hil_sensors.accelerometer_m_s2[2] = imu.zacc; - hil_sensors.accelerometer_mode = 0; // TODO what is this? - hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16 - hil_sensors.accelerometer_timestamp = timestamp; - - hil_sensors.adc_voltage_v[0] = 0.0f; - hil_sensors.adc_voltage_v[1] = 0.0f; - hil_sensors.adc_voltage_v[2] = 0.0f; - - hil_sensors.magnetometer_raw[0] = imu.xmag * 1000.0f; - hil_sensors.magnetometer_raw[1] = imu.ymag * 1000.0f; - hil_sensors.magnetometer_raw[2] = imu.zmag * 1000.0f; - hil_sensors.magnetometer_ga[0] = imu.xmag; - hil_sensors.magnetometer_ga[1] = imu.ymag; - hil_sensors.magnetometer_ga[2] = imu.zmag; - hil_sensors.magnetometer_range_ga = 32.7f; // int16 - hil_sensors.magnetometer_mode = 0; // TODO what is this - hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; - hil_sensors.magnetometer_timestamp = timestamp; - - hil_sensors.baro_pres_mbar = imu.abs_pressure; - hil_sensors.baro_alt_meter = imu.pressure_alt; - hil_sensors.baro_temp_celcius = imu.temperature; - hil_sensors.baro_timestamp = timestamp; - - hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa - hil_sensors.differential_pressure_timestamp = timestamp; - - /* publish combined sensor topic */ - if (_sensors_pub < 0) { - _sensors_pub = orb_advertise(ORB_ID(sensor_combined), &hil_sensors); - - } else { - orb_publish(ORB_ID(sensor_combined), _sensors_pub, &hil_sensors); - } - } - - /* battery status */ - { - struct battery_status_s hil_battery_status; - memset(&hil_battery_status, 0, sizeof(hil_battery_status)); - - hil_battery_status.timestamp = timestamp; - hil_battery_status.voltage_v = 11.1f; - hil_battery_status.voltage_filtered_v = 11.1f; - hil_battery_status.current_a = 10.0f; - hil_battery_status.discharged_mah = -1.0f; - - if (_battery_pub < 0) { - _battery_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status); - - } else { - orb_publish(ORB_ID(battery_status), _battery_pub, &hil_battery_status); - } - } - - /* increment counters */ - _hil_frames++; - - /* print HIL sensors rate */ - if ((timestamp - _old_timestamp) > 10000000) { - // printf("receiving HIL sensors at %d hz\n", _hil_frames / 10); - _old_timestamp = timestamp; - _hil_frames = 0; - } -} - -void -MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) -{ - mavlink_hil_gps_t gps; - mavlink_msg_hil_gps_decode(msg, &gps); - - uint64_t timestamp = hrt_absolute_time(); - - struct vehicle_gps_position_s hil_gps; - memset(&hil_gps, 0, sizeof(hil_gps)); - - hil_gps.timestamp_time = timestamp; - hil_gps.time_utc_usec = gps.time_usec; - - hil_gps.timestamp_position = timestamp; - hil_gps.lat = gps.lat; - hil_gps.lon = gps.lon; - hil_gps.alt = gps.alt; - hil_gps.eph = (float)gps.eph * 1e-2f; // from cm to m - hil_gps.epv = (float)gps.epv * 1e-2f; // from cm to m - - hil_gps.timestamp_variance = timestamp; - hil_gps.s_variance_m_s = 5.0f; - - hil_gps.timestamp_velocity = timestamp; - hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s - hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m - hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m - hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m - hil_gps.vel_ned_valid = true; - hil_gps.cog_rad = _wrap_pi(gps.cog * M_DEG_TO_RAD_F * 1e-2f); - - hil_gps.fix_type = gps.fix_type; - hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used? - - if (_gps_pub < 0) { - _gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps); - - } else { - orb_publish(ORB_ID(vehicle_gps_position), _gps_pub, &hil_gps); - } -} - -void -MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) -{ - mavlink_hil_state_quaternion_t hil_state; - mavlink_msg_hil_state_quaternion_decode(msg, &hil_state); - - uint64_t timestamp = hrt_absolute_time(); - - /* airspeed */ - { - struct airspeed_s airspeed; - memset(&airspeed, 0, sizeof(airspeed)); - - airspeed.timestamp = timestamp; - airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f; - airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f; - - if (_airspeed_pub < 0) { - _airspeed_pub = orb_advertise(ORB_ID(airspeed), &airspeed); - - } else { - orb_publish(ORB_ID(airspeed), _airspeed_pub, &airspeed); - } - } - - /* attitude */ - struct vehicle_attitude_s hil_attitude; - { - memset(&hil_attitude, 0, sizeof(hil_attitude)); - math::Quaternion q(hil_state.attitude_quaternion); - math::Matrix<3, 3> C_nb = q.to_dcm(); - math::Vector<3> euler = C_nb.to_euler(); - - hil_attitude.timestamp = timestamp; - memcpy(hil_attitude.R, C_nb.data, sizeof(hil_attitude.R)); - hil_attitude.R_valid = true; - - hil_attitude.q[0] = q(0); - hil_attitude.q[1] = q(1); - hil_attitude.q[2] = q(2); - hil_attitude.q[3] = q(3); - hil_attitude.q_valid = true; - - hil_attitude.roll = euler(0); - hil_attitude.pitch = euler(1); - hil_attitude.yaw = euler(2); - hil_attitude.rollspeed = hil_state.rollspeed; - hil_attitude.pitchspeed = hil_state.pitchspeed; - hil_attitude.yawspeed = hil_state.yawspeed; - - if (_attitude_pub < 0) { - _attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude); - - } else { - orb_publish(ORB_ID(vehicle_attitude), _attitude_pub, &hil_attitude); - } - } - - /* global position */ - { - struct vehicle_global_position_s hil_global_pos; - memset(&hil_global_pos, 0, sizeof(hil_global_pos)); - - hil_global_pos.timestamp = timestamp; - hil_global_pos.lat = hil_state.lat; - hil_global_pos.lon = hil_state.lon; - hil_global_pos.alt = hil_state.alt / 1000.0f; - hil_global_pos.vel_n = hil_state.vx / 100.0f; - hil_global_pos.vel_e = hil_state.vy / 100.0f; - hil_global_pos.vel_d = hil_state.vz / 100.0f; - hil_global_pos.yaw = hil_attitude.yaw; - hil_global_pos.eph = 2.0f; - hil_global_pos.epv = 4.0f; - - if (_global_pos_pub < 0) { - _global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos); - - } else { - orb_publish(ORB_ID(vehicle_global_position), _global_pos_pub, &hil_global_pos); - } - } - - /* local position */ - { - double lat = hil_state.lat * 1e-7; - double lon = hil_state.lon * 1e-7; - - if (!_hil_local_proj_inited) { - _hil_local_proj_inited = true; - _hil_local_alt0 = hil_state.alt / 1000.0f; - map_projection_init(&_hil_local_proj_ref, hil_state.lat, hil_state.lon); - hil_local_pos.ref_timestamp = timestamp; - hil_local_pos.ref_lat = lat; - hil_local_pos.ref_lon = lon; - hil_local_pos.ref_alt = _hil_local_alt0; - } - - float x; - float y; - map_projection_project(&_hil_local_proj_ref, lat, lon, &x, &y); - hil_local_pos.timestamp = timestamp; - hil_local_pos.xy_valid = true; - hil_local_pos.z_valid = true; - hil_local_pos.v_xy_valid = true; - hil_local_pos.v_z_valid = true; - hil_local_pos.x = x; - hil_local_pos.y = y; - hil_local_pos.z = _hil_local_alt0 - hil_state.alt / 1000.0f; - hil_local_pos.vx = hil_state.vx / 100.0f; - hil_local_pos.vy = hil_state.vy / 100.0f; - hil_local_pos.vz = hil_state.vz / 100.0f; - hil_local_pos.yaw = hil_attitude.yaw; - hil_local_pos.xy_global = true; - hil_local_pos.z_global = true; - - if (_local_pos_pub < 0) { - _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos); - - } else { - orb_publish(ORB_ID(vehicle_local_position), _local_pos_pub, &hil_local_pos); - } - } - - /* land detector */ - { - bool landed = (float)(hil_state.alt) / 1000.0f < (_hil_local_alt0 + 0.1f); // XXX improve? - if(hil_land_detector.landed != landed) { - hil_land_detector.landed = landed; - hil_land_detector.timestamp = hrt_absolute_time(); - - if (_land_detector_pub < 0) { - _land_detector_pub = orb_advertise(ORB_ID(vehicle_land_detected), &hil_land_detector); - - } else { - orb_publish(ORB_ID(vehicle_land_detected), _land_detector_pub, &hil_land_detector); - } - } - } - - /* accelerometer */ - { - struct accel_report accel; - memset(&accel, 0, sizeof(accel)); - - accel.timestamp = timestamp; - accel.x_raw = hil_state.xacc / CONSTANTS_ONE_G * 1e3f; - accel.y_raw = hil_state.yacc / CONSTANTS_ONE_G * 1e3f; - accel.z_raw = hil_state.zacc / CONSTANTS_ONE_G * 1e3f; - accel.x = hil_state.xacc; - accel.y = hil_state.yacc; - accel.z = hil_state.zacc; - accel.temperature = 25.0f; - - if (_accel_pub < 0) { - _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); - - } else { - orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel); - } - } - - /* battery status */ - { - struct battery_status_s hil_battery_status; - memset(&hil_battery_status, 0, sizeof(hil_battery_status)); - - hil_battery_status.timestamp = timestamp; - hil_battery_status.voltage_v = 11.1f; - hil_battery_status.voltage_filtered_v = 11.1f; - hil_battery_status.current_a = 10.0f; - hil_battery_status.discharged_mah = -1.0f; - - if (_battery_pub < 0) { - _battery_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status); - - } else { - orb_publish(ORB_ID(battery_status), _battery_pub, &hil_battery_status); - } - } -} - - -/** - * Receive data from UART. - */ -void * -MavlinkReceiver::receive_thread(void *arg) -{ - int uart_fd = _mavlink->get_uart_fd(); - - const int timeout = 500; - uint8_t buf[32]; - - mavlink_message_t msg; - - /* set thread name */ - char thread_name[24]; - sprintf(thread_name, "mavlink_rcv_if%d", _mavlink->get_instance_id()); - prctl(PR_SET_NAME, thread_name, getpid()); - - struct pollfd fds[1]; - fds[0].fd = uart_fd; - fds[0].events = POLLIN; - - ssize_t nread = 0; - - while (!_mavlink->_task_should_exit) { - if (poll(fds, 1, timeout) > 0) { - - /* non-blocking read. read may return negative values */ - if ((nread = read(uart_fd, buf, sizeof(buf))) < (ssize_t)sizeof(buf)) { - /* to avoid reading very small chunks wait for data before reading */ - usleep(1000); - } - - /* if read failed, this loop won't execute */ - for (ssize_t i = 0; i < nread; i++) { - if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &status)) { - /* handle generic messages and commands */ - handle_message(&msg); - - /* handle packet with parent object */ - _mavlink->handle_message(&msg); - } - } - - /* count received bytes */ - _mavlink->count_rxbytes(nread); - } - } - - return NULL; -} - -void MavlinkReceiver::print_status() -{ - -} - -uint64_t MavlinkReceiver::sync_stamp(uint64_t usec) -{ - if(_time_offset > 0) - return usec - (_time_offset / 1000) ; - else - return hrt_absolute_time(); -} - - -void MavlinkReceiver::smooth_time_offset(uint64_t offset_ns) -{ - /* alpha = 0.6 fixed for now. The closer alpha is to 1.0, - * the faster the moving average updates in response to - * new offset samples. - */ - - _time_offset = (_time_offset_avg_alpha * offset_ns) + (1.0 - _time_offset_avg_alpha) * _time_offset; -} - - -void *MavlinkReceiver::start_helper(void *context) -{ - MavlinkReceiver *rcv = new MavlinkReceiver((Mavlink *)context); - - rcv->receive_thread(NULL); - - delete rcv; - - return nullptr; -} - -pthread_t -MavlinkReceiver::receive_start(Mavlink *parent) -{ - pthread_attr_t receiveloop_attr; - pthread_attr_init(&receiveloop_attr); - - // set to non-blocking read - int flags = fcntl(parent->get_uart_fd(), F_GETFL, 0); - fcntl(parent->get_uart_fd(), F_SETFL, flags | O_NONBLOCK); - - struct sched_param param; - (void)pthread_attr_getschedparam(&receiveloop_attr, ¶m); - param.sched_priority = SCHED_PRIORITY_MAX - 80; - (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); - - pthread_attr_setstacksize(&receiveloop_attr, 1800); - pthread_t thread; - pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent); - - pthread_attr_destroy(&receiveloop_attr); - return thread; -} diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk index bc52677412..1a9936015e 100644 --- a/src/modules/mavlink/mavlink_tests/module.mk +++ b/src/modules/mavlink/mavlink_tests/module.mk @@ -38,12 +38,8 @@ MODULE_COMMAND = mavlink_tests SRCS = mavlink_tests.cpp \ mavlink_ftp_test.cpp \ +SRCS += ../mavlink_ftp.cpp \ ../mavlink.c -ifeq ($(PX4_TARGET_NUTTX),nuttx) -SRCS += ../mavlink_ftp_nuttx.cpp -else -SRCS += ../mavlink_ftp_posix.cpp -endif INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index 20bf945b10..41873e9d43 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -37,13 +37,9 @@ MODULE_COMMAND = mavlink ifeq ($(PX4_TARGET_OS),nuttx) -SRCS += mavlink_main_nuttx.cpp \ - mavlink_ftp_nuttx.cpp \ - mavlink_receiver_nuttx.cpp +SRCS += mavlink_main_nuttx.cpp else -SRCS += mavlink_main_posix.cpp \ - mavlink_ftp_posix.cpp \ - mavlink_receiver_posix.cpp +SRCS += mavlink_main_posix.cpp endif SRCS += mavlink.c \ @@ -52,7 +48,9 @@ SRCS += mavlink.c \ mavlink_orb_subscription.cpp \ mavlink_messages.cpp \ mavlink_stream.cpp \ - mavlink_rate_limiter.cpp + mavlink_rate_limiter.cpp \ + mavlink_receiver.cpp \ + mavlink_ftp.cpp INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink