aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-09-30 15:38:27 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-09-30 15:38:27 +0200
commitcc05f0f18587b35452fe5e27a55769cefe18c4e5 (patch)
treeef787183da27b6a4fdf6de16ae843aed6985ff9b
parent15eee418a035a0109bc0a33fa5889352aa3a1799 (diff)
parentab400089bc2a42f1f0ace569d8f0ee58f4338e1d (diff)
downloadpx4-firmware-cc05f0f18587b35452fe5e27a55769cefe18c4e5.tar.gz
px4-firmware-cc05f0f18587b35452fe5e27a55769cefe18c4e5.tar.bz2
px4-firmware-cc05f0f18587b35452fe5e27a55769cefe18c4e5.zip
Merge remote-tracking branch 'upstream/obcfailsafe' into swissfang
Conflicts: src/lib/external_lgpl/tecs/tecs.cpp src/modules/commander/commander_params.c src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp src/modules/navigator/navigator_main.cpp
-rw-r--r--LICENSE.md41
-rw-r--r--README.md10
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore0
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.databin0 -> 238 bytes
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.databin0 -> 239 bytes
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.databin0 -> 240 bytes
-rw-r--r--makefiles/config_px4fmu-v1_default.mk3
-rw-r--r--makefiles/config_px4fmu-v2_test.mk3
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp1
-rw-r--r--src/modules/commander/commander_params.c2
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp450
-rw-r--r--src/modules/mavlink/mavlink_ftp.h290
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp4
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp757
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h107
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py7
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_tests.cpp52
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk48
-rw-r--r--src/modules/navigator/navigator_main.cpp12
-rw-r--r--src/modules/systemlib/circuit_breaker.c16
-rw-r--r--src/modules/systemlib/mixer/mixer.h6
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp22
-rw-r--r--src/modules/systemlib/param/param.c3
-rw-r--r--src/modules/systemlib/param/param.h2
-rw-r--r--src/modules/uORB/objects_common.cpp3
-rw-r--r--src/modules/uORB/topics/multirotor_motor_limits.h69
-rw-r--r--src/modules/uavcan/sensors/gnss.cpp8
-rw-r--r--src/modules/unit_test/unit_test.cpp5
-rw-r--r--src/modules/unit_test/unit_test.h18
m---------uavcan0
30 files changed, 1598 insertions, 341 deletions
diff --git a/LICENSE.md b/LICENSE.md
new file mode 100644
index 000000000..2ad83eba4
--- /dev/null
+++ b/LICENSE.md
@@ -0,0 +1,41 @@
+The PX4 firmware is licensed generally under a permissive 3-clause BSD license. Contributions are required
+to be made under the same license. Any exception to this general rule is listed below.
+
+ /****************************************************************************
+ *
+ * Copyright (c) 2012-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.
+ *
+ ****************************************************************************/
+
+
+ - PX4 middleware: BSD 3-clause
+ - PX4 flight control stack: BSD 3-clause
+ - NuttX operating system: BSD 3-clause
+ - Exceptions: Currently only this [400 LOC file](https://github.com/PX4/Firmware/blob/master/src/lib/external_lgpl/tecs/tecs.cpp) remains LGPL, but will be replaced with a BSD implementation. \ No newline at end of file
diff --git a/README.md b/README.md
new file mode 100644
index 000000000..84fb02e3b
--- /dev/null
+++ b/README.md
@@ -0,0 +1,10 @@
+## PX4 Aerial Middleware and Flight Control Stack ##
+
+* Official Website: http://px4.io
+* License: BSD 3-clause (see LICENSE.md)
+* Supported airframes:
+ * Multicopters
+ * Fixed wing
+* Binaries (always up-to-date from master):
+ * [Downloads](https://pixhawk.org/downloads)
+* Mailing list: [Google Groups](http://groups.google.com/group/px4users)
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data
new file mode 100644
index 000000000..973de16e5
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data
Binary files differ
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data
new file mode 100644
index 000000000..7e8764c03
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data
Binary files differ
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data
new file mode 100644
index 000000000..f3fe31687
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data
Binary files differ
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 99c0eb8c1..ffb9391d2 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -27,8 +27,6 @@ MODULES += drivers/ms5611
MODULES += drivers/mb12xx
MODULES += drivers/gps
MODULES += drivers/hil
-MODULES += drivers/hott/hott_telemetry
-MODULES += drivers/hott/hott_sensors
MODULES += drivers/blinkm
MODULES += drivers/rgbled
MODULES += drivers/mkblctrl
@@ -42,7 +40,6 @@ MODULES += modules/sensors
# System commands
#
MODULES += systemcmds/mtd
-MODULES += systemcmds/bl_update
MODULES += systemcmds/mixer
MODULES += systemcmds/param
MODULES += systemcmds/perf
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 932f92261..a41670a77 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -54,6 +54,9 @@ MODULES += lib/conversion
#
LIBRARIES += lib/mathlib/CMSIS
+MODULES += modules/unit_test
+MODULES += modules/mavlink/mavlink_tests
+
#
# Transitional support - add commands from the NuttX export archive.
#
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index da99aa5b1..6a2a61b04 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -238,6 +238,7 @@ void TECS::_update_height_demand(float demand, float state)
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
_hgt_dem_adj_last = _hgt_dem_adj;
+
// Limit height rate of change
if (_hgt_rate_dem > _maxClimbRate) {
_hgt_rate_dem = _maxClimbRate;
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index f4bc7fd7f..1b0c4258b 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -159,7 +159,7 @@ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
* @min 0.0f
* @max 7.0f
*/
-PARAM_DEFINE_FLOAT(COM_EF_TIME, 5.0f);
+PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f);
/** RC loss time threshold
*
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 5b65dc369..2a85c3702 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -31,38 +31,38 @@
*
****************************************************************************/
-#include <crc32.h>
+/// @file mavlink_ftp.cpp
+/// @author px4dev, Don Gagne <don@thegagnes.com>
+
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
#include <sys/stat.h>
+#include <errno.h>
#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::_server;
-
MavlinkFTP *
-MavlinkFTP::getServer()
+MavlinkFTP::get_server(void)
{
- // XXX this really cries out for some locking...
- if (_server == nullptr) {
- _server = new MavlinkFTP;
- }
- return _server;
+ static MavlinkFTP server;
+ return &server;
}
MavlinkFTP::MavlinkFTP() :
- _session_fds{},
- _workBufs{},
- _workFree{},
- _lock{}
+ _request_bufs{},
+ _request_queue{},
+ _request_queue_sem{},
+ _utRcvMsgFunc{},
+ _ftp_test{}
{
// initialise the request freelist
- dq_init(&_workFree);
- sem_init(&_lock, 0, 1);
+ dq_init(&_request_queue);
+ sem_init(&_request_queue_sem, 0, 1);
// initialize session list
for (size_t i=0; i<kMaxSession; i++) {
@@ -71,167 +71,240 @@ MavlinkFTP::MavlinkFTP() :
// drop work entries onto the free list
for (unsigned i = 0; i < kRequestQueueSize; i++) {
- _qFree(&_workBufs[i]);
+ _return_request(&_request_bufs[i]);
}
}
+#ifdef MAVLINK_FTP_UNIT_TEST
+void
+MavlinkFTP::set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test)
+{
+ _utRcvMsgFunc = rcvMsgFunc;
+ _ftp_test = ftp_test;
+}
+#endif
+
void
MavlinkFTP::handle_message(Mavlink* mavlink, mavlink_message_t *msg)
{
// get a free request
- auto req = _dqFree();
+ struct Request* req = _get_request();
// if we couldn't get a request slot, just drop it
- if (req != nullptr) {
-
- // decode the request
- if (req->decode(mavlink, msg)) {
+ if (req == nullptr) {
+ warnx("Dropping FTP request: queue full\n");
+ return;
+ }
- // and queue it for the worker
- work_queue(LPWORK, &req->work, &MavlinkFTP::_workerTrampoline, req, 0);
- } else {
- _qFree(req);
+ if (msg->msgid == 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::_workerTrampoline(void *arg)
+MavlinkFTP::_worker_trampoline(void *arg)
{
- auto req = reinterpret_cast<Request *>(arg);
- auto server = MavlinkFTP::getServer();
+ Request* req = reinterpret_cast<Request *>(arg);
+ MavlinkFTP* server = MavlinkFTP::get_server();
// call the server worker with the work item
- server->_worker(req);
+ server->_process_request(req);
}
+/// @brief Processes an FTP message
void
-MavlinkFTP::_worker(Request *req)
+MavlinkFTP::_process_request(Request *req)
{
- auto hdr = req->header();
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
+
ErrorCode errorCode = kErrNone;
- uint32_t messageCRC;
// basic sanity checks; must validate length before use
- if (hdr->size > kMaxDataLength) {
- errorCode = kErrNoRequest;
+ if (payload->size > kMaxDataLength) {
+ errorCode = kErrInvalidDataSize;
goto out;
}
- // check request CRC to make sure this is one of ours
- messageCRC = hdr->crc32;
- hdr->crc32 = 0;
- hdr->padding[0] = 0;
- hdr->padding[1] = 0;
- hdr->padding[2] = 0;
- if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
- errorCode = kErrNoRequest;
- goto out;
- warnx("ftp: bad crc");
- }
-
#ifdef MAVLINK_FTP_DEBUG
- printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+ printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset);
#endif
- switch (hdr->opcode) {
+ switch (payload->opcode) {
case kCmdNone:
break;
- case kCmdTerminate:
- errorCode = _workTerminate(req);
+ case kCmdTerminateSession:
+ errorCode = _workTerminate(payload);
break;
- case kCmdReset:
- errorCode = _workReset();
+ case kCmdResetSessions:
+ errorCode = _workReset(payload);
break;
- case kCmdList:
- errorCode = _workList(req);
+ case kCmdListDirectory:
+ errorCode = _workList(payload);
break;
- case kCmdOpen:
- errorCode = _workOpen(req, false);
+ case kCmdOpenFile:
+ errorCode = _workOpen(payload, false);
break;
- case kCmdCreate:
- errorCode = _workOpen(req, true);
+ case kCmdCreateFile:
+ errorCode = _workOpen(payload, true);
break;
- case kCmdRead:
- errorCode = _workRead(req);
+ case kCmdReadFile:
+ errorCode = _workRead(payload);
break;
- case kCmdWrite:
- errorCode = _workWrite(req);
+ case kCmdWriteFile:
+ errorCode = _workWrite(payload);
break;
- case kCmdRemove:
- errorCode = _workRemove(req);
+ case kCmdRemoveFile:
+ errorCode = _workRemoveFile(payload);
break;
+ case kCmdCreateDirectory:
+ errorCode = _workCreateDirectory(payload);
+ break;
+
+ case kCmdRemoveDirectory:
+ errorCode = _workRemoveDirectory(payload);
+ break;
+
default:
- errorCode = kErrNoRequest;
+ errorCode = kErrUnknownCommand;
break;
}
out:
// handle success vs. error
if (errorCode == kErrNone) {
- hdr->opcode = kRspAck;
+ payload->req_opcode = payload->opcode;
+ payload->opcode = kRspAck;
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: ack\n");
#endif
} else {
warnx("FTP: nak %u", errorCode);
- hdr->opcode = kRspNak;
- hdr->size = 1;
- hdr->data[0] = 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] = errno;
+ }
}
+
// respond to the request
_reply(req);
- // free the request buffer back to the freelist
- _qFree(req);
+ _return_request(req);
}
+/// @brief Sends the specified FTP reponse message out through mavlink
void
MavlinkFTP::_reply(Request *req)
{
- auto hdr = req->header();
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
- hdr->seqNumber = req->header()->seqNumber + 1;
+ payload->seqNumber = payload->seqNumber + 1;
- // message is assumed to be already constructed in the request buffer, so generate the CRC
- hdr->crc32 = 0;
- hdr->padding[0] = 0;
- hdr->padding[1] = 0;
- hdr->padding[2] = 0;
- hdr->crc32 = crc32(req->rawData(), req->dataSize());
+ 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
- // then pack and send the reply back to the request source
- req->reply();
+ 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(Request *req)
+MavlinkFTP::_workList(PayloadHeader* payload)
{
- auto hdr = req->header();
-
char dirPath[kMaxDataLength];
- strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+ strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength);
DIR *dp = opendir(dirPath);
if (dp == nullptr) {
warnx("FTP: can't open path '%s'", dirPath);
- return kErrNotDir;
+ return kErrFailErrno;
}
#ifdef MAVLINK_FTP_DEBUG
- warnx("FTP: list %s offset %d", dirPath, hdr->offset);
+ warnx("FTP: list %s offset %d", dirPath, payload->offset);
#endif
ErrorCode errorCode = kErrNone;
@@ -239,19 +312,19 @@ MavlinkFTP::_workList(Request *req)
unsigned offset = 0;
// move to the requested offset
- seekdir(dp, hdr->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 = kErrIO;
+ errorCode = kErrFailErrno;
break;
}
// no more entries?
if (result == nullptr) {
- if (hdr->offset != 0 && offset == 0) {
+ 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;
@@ -276,14 +349,22 @@ MavlinkFTP::_workList(Request *req)
}
break;
case DTYPE_DIRECTORY:
- direntType = kDirentDir;
+ if (strcmp(entry.d_name, ".") == 0 || strcmp(entry.d_name, "..") == 0) {
+ // Don't bother sending these back
+ direntType = kDirentSkip;
+ } else {
+ direntType = kDirentDir;
+ }
break;
default:
- direntType = kDirentUnknown;
- break;
+ // We only send back file and diretory entries, skip everything else
+ direntType = kDirentSkip;
}
- if (entry.d_type == DTYPE_FILE) {
+ 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 {
@@ -299,94 +380,95 @@ MavlinkFTP::_workList(Request *req)
}
// Move the data into the buffer
- hdr->data[offset++] = direntType;
- strcpy((char *)&hdr->data[offset], buf);
+ payload->data[offset++] = direntType;
+ strcpy((char *)&payload->data[offset], buf);
#ifdef MAVLINK_FTP_DEBUG
- printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
+ printf("FTP: list %s %s\n", dirPath, (char *)&payload->data[offset-1]);
#endif
offset += nameLen + 1;
}
closedir(dp);
- hdr->size = offset;
+ payload->size = offset;
return errorCode;
}
+/// @brief Responds to an Open command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workOpen(Request *req, bool create)
+MavlinkFTP::_workOpen(PayloadHeader* payload, bool create)
{
- auto hdr = req->header();
-
- int session_index = _findUnusedSession();
+ int session_index = _find_unused_session();
if (session_index < 0) {
- return kErrNoSession;
+ warnx("FTP: Open failed - out of sessions\n");
+ return kErrNoSessionsAvailable;
}
-
+
+ char *filename = _data_as_cstring(payload);
uint32_t fileSize = 0;
if (!create) {
struct stat st;
- if (stat(req->dataAsCString(), &st) != 0) {
- return kErrNotFile;
+ if (stat(filename, &st) != 0) {
+ return kErrFailErrno;
}
fileSize = st.st_size;
}
int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
- int fd = ::open(req->dataAsCString(), oflag);
+ int fd = ::open(filename, oflag);
if (fd < 0) {
- return create ? kErrPerm : kErrNotFile;
+ return kErrFailErrno;
}
_session_fds[session_index] = fd;
- hdr->session = session_index;
+ payload->session = session_index;
if (create) {
- hdr->size = 0;
+ payload->size = 0;
} else {
- hdr->size = sizeof(uint32_t);
- *((uint32_t*)hdr->data) = fileSize;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = fileSize;
}
return kErrNone;
}
+/// @brief Responds to a Read command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRead(Request *req)
+MavlinkFTP::_workRead(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- int session_index = hdr->session;
+ int session_index = payload->session;
- if (!_validSession(session_index)) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
// Seek to the specified position
#ifdef MAVLINK_FTP_DEBUG
- warnx("seek %d", hdr->offset);
+ warnx("seek %d", payload->offset);
#endif
- if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
+ 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], &hdr->data[0], kMaxDataLength);
+ 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 kErrIO;
+ return kErrFailErrno;
}
- hdr->size = bytes_read;
+ payload->size = bytes_read;
return kErrNone;
}
+/// @brief Responds to a Write command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workWrite(Request *req)
+MavlinkFTP::_workWrite(PayloadHeader* payload)
{
#if 0
// NYI: Coming soon
@@ -409,35 +491,44 @@ MavlinkFTP::_workWrite(Request *req)
hdr->size = result;
return kErrNone;
#else
- return kErrPerm;
+ return kErrUnknownCommand;
#endif
}
+/// @brief Responds to a RemoveFile command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRemove(Request *req)
+MavlinkFTP::_workRemoveFile(PayloadHeader* payload)
{
- //auto hdr = req->header();
-
- // for now, send error reply
- return kErrPerm;
+ 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 Terminate command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workTerminate(Request *req)
+MavlinkFTP::_workTerminate(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- if (!_validSession(hdr->session)) {
- return kErrNoSession;
+ if (!_valid_session(payload->session)) {
+ return kErrInvalidSession;
}
- ::close(_session_fds[hdr->session]);
+ ::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(void)
+MavlinkFTP::_workReset(PayloadHeader* payload)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] != -1) {
@@ -446,11 +537,44 @@ MavlinkFTP::_workReset(void)
}
}
+ payload->size = 0;
+
return kErrNone;
}
+/// @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 Returns true if the specified session is a valid open session
bool
-MavlinkFTP::_validSession(unsigned index)
+MavlinkFTP::_valid_session(unsigned index)
{
if ((index >= kMaxSession) || (_session_fds[index] < 0)) {
return false;
@@ -458,8 +582,9 @@ MavlinkFTP::_validSession(unsigned index)
return true;
}
+/// @brief Returns an unused session index
int
-MavlinkFTP::_findUnusedSession(void)
+MavlinkFTP::_find_unused_session(void)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] == -1) {
@@ -470,16 +595,53 @@ MavlinkFTP::_findUnusedSession(void)
return -1;
}
+/// @brief Guarantees that the payload data is null terminated.
+/// @return Returns a pointer to the payload data as a char *
char *
-MavlinkFTP::Request::dataAsCString()
+MavlinkFTP::_data_as_cstring(PayloadHeader* payload)
{
// guarantee nul termination
- if (header()->size < kMaxDataLength) {
- requestData()[header()->size] = '\0';
+ if (payload->size < kMaxDataLength) {
+ payload->data[payload->size] = '\0';
} else {
- requestData()[kMaxDataLength - 1] = '\0';
+ payload->data[kMaxDataLength - 1] = '\0';
}
// and return data
- return (char *)&(header()->data[0]);
+ 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<Request *>(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();
+}
+
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index 1dd8f102e..657e2f855 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -33,17 +33,8 @@
#pragma once
-/**
- * @file mavlink_ftp.h
- *
- * MAVLink remote file server.
- *
- * A limited number of requests (currently 2) may be outstanding at a time.
- * Additional messages will be discarded.
- *
- * Messages consist of a fixed header, followed by a data area.
- *
- */
+/// @file mavlink_ftp.h
+/// @author px4dev, Don Gagne <don@thegagnes.com>
#include <dirent.h>
#include <queue.h>
@@ -54,183 +45,128 @@
#include "mavlink_messages.h"
#include "mavlink_main.h"
+class MavlinkFtpTest;
+
+/// @brief MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message.
+/// A limited number of requests (kRequestQueueSize) may be outstanding at a time. Additional messages will be discarded.
class MavlinkFTP
{
public:
+ /// @brief Returns the one Mavlink FTP server in the system.
+ static MavlinkFTP* get_server(void);
+
+ /// @brief Contructor is only public so unit test code can new objects.
MavlinkFTP();
-
- static MavlinkFTP *getServer();
-
- // static interface
- void handle_message(Mavlink* mavlink,
- mavlink_message_t *msg);
-
-private:
-
- static const unsigned kRequestQueueSize = 2;
-
- static MavlinkFTP *_server;
-
- /// @brief Trying to pack structures across differing compilers is questionable for Clients, so we pad the
- /// structure ourselves to 32 bit alignment which should get us what we want.
- struct RequestHeader
+
+ /// @brief Adds the specified message to the work queue.
+ void handle_message(Mavlink* mavlink, mavlink_message_t *msg);
+
+ typedef void (*ReceiveMessageFunc_t)(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ /// @brief Sets up the server to run in unit test mode.
+ /// @param rcvmsgFunc Function which will be called to handle outgoing mavlink messages.
+ /// @param ftp_test MavlinkFtpTest object which the function is associated with
+ void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test);
+
+ /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. We pad the structure ourselves to
+ /// 32 bit alignment to avoid usage of any pack pragmas.
+ struct PayloadHeader
{
- uint16_t seqNumber; ///< sequence number for message
- uint8_t session; ///< Session id for read and write commands
- uint8_t opcode; ///< Command opcode
- uint8_t size; ///< Size of data
- uint8_t padding[3];
- uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0
- uint32_t offset; ///< Offsets for List and Read commands
- uint8_t data[];
+ uint16_t seqNumber; ///< sequence number for message
+ uint8_t session; ///< Session id for read and write commands
+ uint8_t opcode; ///< Command opcode
+ uint8_t size; ///< Size of data
+ uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
+ uint8_t padding[2]; ///< 32 bit aligment padding
+ uint32_t offset; ///< Offsets for List and Read commands
+ uint8_t data[]; ///< command data, varies by Opcode
};
-
+
+ /// @brief Command opcodes
enum Opcode : uint8_t
{
- kCmdNone, // ignored, always acked
- kCmdTerminate, // releases sessionID, closes file
- kCmdReset, // terminates all sessions
- kCmdList, // list files in <path> from <offset>
- kCmdOpen, // opens <path> for reading, returns <session>
- kCmdRead, // reads <size> bytes from <offset> in <session>
- kCmdCreate, // creates <path> for writing, returns <session>
- kCmdWrite, // appends <size> bytes at <offset> in <session>
- kCmdRemove, // remove file (only if created by server?)
-
- kRspAck,
- kRspNak
+ kCmdNone, ///< ignored, always acked
+ kCmdTerminateSession, ///< Terminates open Read session
+ kCmdResetSessions, ///< Terminates all open Read sessions
+ kCmdListDirectory, ///< List files in <path> from <offset>
+ kCmdOpenFile, ///< Opens file at <path> for reading, returns <session>
+ kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
+ kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
+ kCmdWriteFile, ///< Appends <size> bytes to file in <session>
+ kCmdRemoveFile, ///< Remove file at <path>
+ kCmdCreateDirectory, ///< Creates directory at <path>
+ kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
+
+ kRspAck = 128, ///< Ack response
+ kRspNak ///< Nak response
};
-
+
+ /// @brief Error codes returned in Nak response PayloadHeader.data[0].
enum ErrorCode : uint8_t
- {
+ {
kErrNone,
- kErrNoRequest,
- kErrNoSession,
- kErrSequence,
- kErrNotDir,
- kErrNotFile,
- kErrEOF,
- kErrNotAppend,
- kErrTooBig,
- kErrIO,
- kErrPerm
- };
-
- int _findUnusedSession(void);
- bool _validSession(unsigned index);
-
- static const unsigned kMaxSession = 2;
- int _session_fds[kMaxSession];
-
- class Request
+ kErrFail, ///< Unknown failure
+ kErrFailErrno, ///< Command failed, errno sent back in PayloadHeader.data[1]
+ kErrInvalidDataSize, ///< PayloadHeader.size is invalid
+ kErrInvalidSession, ///< Session is not currently open
+ kErrNoSessionsAvailable, ///< All available Sessions in use
+ kErrEOF, ///< Offset past end of file for List and Read commands
+ kErrUnknownCommand ///< Unknown command opcode
+ };
+
+private:
+ /// @brief Unit of work which is queued to work_queue
+ struct Request
{
- public:
- union {
- dq_entry_t entry;
- work_s work;
- };
-
- bool decode(Mavlink *mavlink, mavlink_message_t *fromMessage) {
- if (fromMessage->msgid == MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
- _systemId = fromMessage->sysid;
- _mavlink = mavlink;
- mavlink_msg_file_transfer_protocol_decode(fromMessage, &_message);
- return _message.target_system == _mavlink->get_system_id();
- }
- return false;
- }
-
- void reply() {
-
- // XXX the proper way would be an IOCTL / uORB call, rather than exploiting the
- // flat memory architecture, as we're operating between threads here.
- mavlink_message_t msg;
- msg.checksum = 0;
- unsigned len = mavlink_msg_file_transfer_protocol_pack_chan(_mavlink->get_system_id(), // Sender system id
- _mavlink->get_component_id(), // Sender component id
- _mavlink->get_channel(), // Channel to send on
- &msg, // Message to pack payload into
- 0, // Target network
- _systemId, // Target system id
- 0, // Target component id
- rawData()); // Payload to pack into message
-
- _mavlink->lockMessageBufferMutex();
- bool success = _mavlink->message_buffer_write(&msg, len);
- _mavlink->unlockMessageBufferMutex();
-
- if (!success) {
- warnx("FTP TX ERR");
- }
-#ifdef MAVLINK_FTP_DEBUG
- else {
- warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
- _mavlink->get_system_id(),
- _mavlink->get_component_id(),
- _mavlink->get_channel(),
- len,
- msg.checksum);
- }
-#endif
- }
-
- uint8_t *rawData() { return &_message.payload[0]; }
- RequestHeader *header() { return reinterpret_cast<RequestHeader *>(&_message.payload[0]); }
- uint8_t *requestData() { return &(header()->data[0]); }
- unsigned dataSize() { return header()->size + sizeof(RequestHeader); }
- mavlink_channel_t channel() { return _mavlink->get_channel(); }
-
- char *dataAsCString();
-
- private:
- Mavlink *_mavlink;
- mavlink_file_transfer_protocol_t _message;
- uint8_t _systemId;
-
+ work_s work; ///< work queue entry
+ Mavlink *mavlink; ///< Mavlink to reply to
+ uint8_t serverSystemId; ///< System ID to send from
+ uint8_t serverComponentId; ///< Component ID to send from
+ uint8_t serverChannel; ///< Channel to send to
+ uint8_t targetSystemId; ///< System ID to target reply to
+
+ mavlink_file_transfer_protocol_t message; ///< Protocol message
};
-
- static const char kDirentFile = 'F';
- static const char kDirentDir = 'D';
- static const char kDirentUnknown = 'U';
- static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(RequestHeader);
-
- /// Request worker; runs on the low-priority work queue to service
- /// remote requests.
- ///
- static void _workerTrampoline(void *arg);
- void _worker(Request *req);
-
- /// Reply to a request (XXX should be a Request method)
- ///
- void _reply(Request *req);
-
- ErrorCode _workList(Request *req);
- ErrorCode _workOpen(Request *req, bool create);
- ErrorCode _workRead(Request *req);
- ErrorCode _workWrite(Request *req);
- ErrorCode _workRemove(Request *req);
- ErrorCode _workTerminate(Request *req);
- ErrorCode _workReset();
-
- // work freelist
- Request _workBufs[kRequestQueueSize];
- dq_queue_t _workFree;
- sem_t _lock;
-
- void _qLock() { do {} while (sem_wait(&_lock) != 0); }
- void _qUnlock() { sem_post(&_lock); }
-
- void _qFree(Request *req) {
- _qLock();
- dq_addlast(&req->entry, &_workFree);
- _qUnlock();
- }
-
- Request *_dqFree() {
- _qLock();
- auto req = reinterpret_cast<Request *>(dq_remfirst(&_workFree));
- _qUnlock();
- return req;
- }
-
+
+ Request *_get_request(void);
+ void _return_request(Request *req);
+ void _lock_request_queue(void);
+ void _unlock_request_queue(void);
+
+ char *_data_as_cstring(PayloadHeader* payload);
+
+ static void _worker_trampoline(void *arg);
+ void _process_request(Request *req);
+ void _reply(Request *req);
+
+ ErrorCode _workList(PayloadHeader *payload);
+ ErrorCode _workOpen(PayloadHeader *payload, bool create);
+ ErrorCode _workRead(PayloadHeader *payload);
+ ErrorCode _workWrite(PayloadHeader *payload);
+ ErrorCode _workTerminate(PayloadHeader *payload);
+ ErrorCode _workReset(PayloadHeader* payload);
+ ErrorCode _workRemoveDirectory(PayloadHeader *payload);
+ ErrorCode _workCreateDirectory(PayloadHeader *payload);
+ ErrorCode _workRemoveFile(PayloadHeader *payload);
+
+ static const unsigned kRequestQueueSize = 2; ///< Max number of queued requests
+ Request _request_bufs[kRequestQueueSize]; ///< Request buffers which hold work
+ dq_queue_t _request_queue; ///< Queue of available Request buffers
+ sem_t _request_queue_sem; ///< Semaphore for locking access to _request_queue
+
+ int _find_unused_session(void);
+ bool _valid_session(unsigned index);
+
+ static const char kDirentFile = 'F'; ///< Identifies File returned from List command
+ static const char kDirentDir = 'D'; ///< Identifies Directory returned from List command
+ static const char kDirentSkip = 'S'; ///< Identifies Skipped entry from List command
+
+ /// @brief Maximum data size in RequestHeader::data
+ static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader);
+
+ static const unsigned kMaxSession = 2; ///< Max number of active sessions
+ int _session_fds[kMaxSession]; ///< Session file descriptors, 0 for empty slot
+
+ ReceiveMessageFunc_t _utRcvMsgFunc; ///< Unit test override for mavlink message sending
+ MavlinkFtpTest *_ftp_test; ///< Additional parameter to _utRcvMsgFunc;
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 43222880e..0ac62d545 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -123,7 +123,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
{
// make sure the FTP server is started
- (void)MavlinkFTP::getServer();
+ (void)MavlinkFTP::get_server();
}
MavlinkReceiver::~MavlinkReceiver()
@@ -175,7 +175,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
break;
case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
- MavlinkFTP::getServer()->handle_message(_mavlink, msg);
+ MavlinkFTP::get_server()->handle_message(_mavlink, msg);
break;
default:
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
new file mode 100644
index 000000000..022041c74
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
@@ -0,0 +1,757 @@
+/****************************************************************************
+ *
+ * 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_test.cpp
+/// @author Don Gagne <don@thegagnes.com>
+
+#include <sys/stat.h>
+#include <crc32.h>
+#include <stdio.h>
+#include <fcntl.h>
+
+#include "mavlink_ftp_test.h"
+#include "../mavlink_ftp.h"
+
+/// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
+const MavlinkFtpTest::ReadTestCase MavlinkFtpTest::_rgReadTestCases[] = {
+ { "/etc/unit_test_data/mavlink_tests/test_238.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1}, // Read takes less than single packet
+ { "/etc/unit_test_data/mavlink_tests/test_239.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
+ { "/etc/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
+};
+
+const char MavlinkFtpTest::_unittest_microsd_dir[] = "/fs/microsd/ftp_unit_test_dir";
+const char MavlinkFtpTest::_unittest_microsd_file[] = "/fs/microsd/ftp_unit_test_dir/file";
+
+MavlinkFtpTest::MavlinkFtpTest() :
+ _ftp_server{},
+ _reply_msg{},
+ _lastOutgoingSeqNumber{}
+{
+}
+
+MavlinkFtpTest::~MavlinkFtpTest()
+{
+
+}
+
+/// @brief Called before every test to initialize the FTP Server.
+void MavlinkFtpTest::init(void)
+{
+ _ftp_server = new MavlinkFTP;;
+ _ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message, this);
+
+ _cleanup_microsd();
+}
+
+/// @brief Called after every test to take down the FTP Server.
+void MavlinkFtpTest::cleanup(void)
+{
+ delete _ftp_server;
+
+ _cleanup_microsd();
+}
+
+/// @brief Tests for correct behavior of an Ack response.
+bool MavlinkFtpTest::_ack_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = MavlinkFTP::kCmdNone;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+
+ return true;
+}
+
+/// @brief Tests for correct response to an invalid opcpde.
+bool MavlinkFtpTest::_bad_opcode_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = 0xFF; // bogus opcode
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrUnknownCommand);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a payload which an invalid data size field.
+bool MavlinkFtpTest::_bad_datasize_test(void)
+{
+ mavlink_message_t msg;
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+
+ _setup_ftp_msg(&payload, 0, nullptr, &msg);
+
+ // Set the data size to be one larger than is legal
+ ((MavlinkFTP::PayloadHeader*)((mavlink_file_transfer_protocol_t*)msg.payload64)->payload)->size = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN + 1;
+
+ _ftp_server->handle_message(nullptr /* mavlink */, &msg);
+
+ if (!_decode_message(&_reply_msg, &ftp_msg, &reply)) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidDataSize);
+
+ return true;
+}
+
+bool MavlinkFtpTest::_list_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ char response1[] = "Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
+ char response2[] = "Ddev|Detc|Dfs|Dobj";
+
+ struct _testCase {
+ const char *dir; ///< Directory to run List command on
+ char *response; ///< Expected response entries from List command
+ int response_count; ///< Number of directories that should be returned
+ bool success; ///< true: List command should succeed, false: List command should fail
+ };
+ struct _testCase rgTestCases[] = {
+ { "/bogus", nullptr, 0, false },
+ { "/etc/unit_test_data/mavlink_tests", response1, 4, true },
+ { "/", response2, 4, true },
+ };
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, strlen(test->response) + 1);
+
+ // The return order of directories from the List command is not repeatable. So we can't do a direct comparison
+ // to a hardcoded return result string.
+
+ // Convert null terminators to seperator char so we can use strok to parse returned data
+ for (uint8_t j=0; j<reply->size-1; j++) {
+ if (reply->data[j] == 0) {
+ reply->data[j] = '|';
+ }
+ }
+
+ // Loop over returned directory entries trying to find then in the response list
+ char *dir;
+ int response_count = 0;
+ dir = strtok((char *)&reply->data[0], "|");
+ while (dir != nullptr) {
+ ut_assert("Returned directory not found in expected response", strstr(test->response, dir));
+ response_count++;
+ dir = strtok(nullptr, "|");
+ }
+
+ ut_compare("Incorrect number of directory entires returned", test->response_count, response_count);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a List command on a valid directory, but with an offset that
+/// is beyond the last directory entry.
+bool MavlinkFtpTest::_list_eof_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/";
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+ payload.offset = 4; // offset past top level dirs
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(dir)+1, // size in bytes of data
+ (uint8_t*)dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrEOF);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to an Open command on a file which does not exist.
+bool MavlinkFtpTest::_open_badfile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/foo"; // non-existent file
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(dir)+1, // size in bytes of data
+ (uint8_t*)dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
+bool MavlinkFtpTest::_open_terminate_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("stat failed", stat(test->file, &st), 0);
+
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, sizeof(uint32_t));
+ ut_compare("File size incorrect", *((uint32_t*)&reply->data[0]), (uint32_t)st.st_size);
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Terminate command on an invalid session.
+bool MavlinkFtpTest::_terminate_badsession_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(file)+1, // size in bytes of data
+ (uint8_t*)file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session + 1;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Read command on an open session.
+bool MavlinkFtpTest::_read_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[i];
+
+ // Read in the file so we can compare it to what we get back
+ ut_compare("stat failed", stat(test->file, &st), 0);
+ uint8_t *bytes = new uint8_t[st.st_size];
+ ut_assert("new failed", bytes != nullptr);
+ int fd = ::open(test->file, O_RDONLY);
+ ut_assert("open failed", fd != -1);
+ int bytes_read = ::read(fd, bytes, st.st_size);
+ ut_compare("read failed", bytes_read, st.st_size);
+ ::close(fd);
+
+ // Test case data files are created for specific boundary conditions
+ ut_compare("Test case data files are out of date", test->length, st.st_size);
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdReadFile;
+ payload.session = reply->session;
+ payload.offset = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Offset incorrect", reply->offset, 0);
+
+ if (test->length <= MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader)) {
+ ut_compare("Payload size incorrect", reply->size, (uint32_t)st.st_size);
+ ut_compare("File contents differ", memcmp(reply->data, bytes, st.st_size), 0);
+ }
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Read command on an invalid session.
+bool MavlinkFtpTest::_read_badsession_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(file)+1, // size in bytes of data
+ (uint8_t*)file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdReadFile;
+ payload.session = reply->session + 1; // Invalid session
+ payload.offset = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
+
+ return true;
+}
+
+bool MavlinkFtpTest::_removedirectory_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ bool deleteFile;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false, false },
+ { "/etc/unit_test_data/mavlink_tests/empty_dir", false, false },
+ { _unittest_microsd_dir, false, false },
+ { _unittest_microsd_file, false, false },
+ { _unittest_microsd_dir, true, true },
+ };
+
+ ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
+ ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
+ ::close(fd);
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ if (test->deleteFile) {
+ ut_compare("unlink failed", ::unlink(_unittest_microsd_file), 0);
+ }
+
+ payload.opcode = MavlinkFTP::kCmdRemoveDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_createdirectory_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/etc/bogus", false },
+ { _unittest_microsd_dir, true },
+ { _unittest_microsd_dir, false },
+ { "/fs/microsd/bogus/bogus", false },
+ };
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdCreateDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_removefile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *file;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false },
+ { _rgReadTestCases[0].file, false },
+ { _unittest_microsd_dir, false },
+ { _unittest_microsd_file, true },
+ { _unittest_microsd_file, false },
+ };
+
+ ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
+ ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
+ ::close(fd);
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdRemoveFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Static method used as callback from MavlinkFTP. This method will be called by MavlinkFTP when
+/// it needs to send a message out on Mavlink.
+void MavlinkFtpTest::receive_message(const mavlink_message_t *msg, MavlinkFtpTest *ftp_test)
+{
+ ftp_test->_receive_message(msg);
+}
+
+/// @brief Non-Static version of receive_message
+void MavlinkFtpTest::_receive_message(const mavlink_message_t *msg)
+{
+ // Move the message into our own member variable
+ memcpy(&_reply_msg, msg, sizeof(mavlink_message_t));
+}
+
+/// @brief Decode and validate the incoming message
+bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlink message to decode
+ mavlink_file_transfer_protocol_t *ftp_msg, ///< Decoded FTP message
+ MavlinkFTP::PayloadHeader **payload) ///< Payload inside FTP message response
+{
+ mavlink_msg_file_transfer_protocol_decode(msg, ftp_msg);
+
+ // Make sure the targets are correct
+ ut_compare("Target network non-zero", ftp_msg->target_network, 0);
+ ut_compare("Target system id mismatch", ftp_msg->target_system, clientSystemId);
+ ut_compare("Target component id mismatch", ftp_msg->target_component, clientComponentId);
+
+ *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
+
+ // Make sure we have a good sequence number
+ ut_compare("Sequence number mismatch", (*payload)->seqNumber, _lastOutgoingSeqNumber + 1);
+
+ // Bump sequence number for next outgoing message
+ _lastOutgoingSeqNumber++;
+
+ return true;
+}
+
+/// @brief Initializes an FTP message into a mavlink message
+void MavlinkFtpTest::_setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
+ uint8_t size, ///< size in bytes of data
+ const uint8_t *data, ///< Data to start into FTP message payload
+ mavlink_message_t *msg) ///< Returned mavlink message
+{
+ uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN];
+ MavlinkFTP::PayloadHeader *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(payload_bytes);
+
+ memcpy(payload, payload_header, sizeof(MavlinkFTP::PayloadHeader));
+
+ payload->seqNumber = _lastOutgoingSeqNumber;
+ payload->size = size;
+ if (size != 0) {
+ memcpy(payload->data, data, size);
+ }
+
+ payload->padding[0] = 0;
+ payload->padding[1] = 0;
+
+ msg->checksum = 0;
+ mavlink_msg_file_transfer_protocol_pack(clientSystemId, // Sender system id
+ clientComponentId, // Sender component id
+ msg, // Message to pack payload into
+ 0, // Target network
+ serverSystemId, // Target system id
+ serverComponentId, // Target component id
+ payload_bytes); // Payload to pack into message
+}
+
+/// @brief Sends the specified FTP message to the server and returns response
+bool MavlinkFtpTest::_send_receive_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
+ uint8_t size, ///< size in bytes of data
+ const uint8_t *data, ///< Data to start into FTP message payload
+ mavlink_file_transfer_protocol_t *ftp_msg_reply, ///< Response from server
+ MavlinkFTP::PayloadHeader **payload_reply) ///< Payload inside FTP message response
+{
+ mavlink_message_t msg;
+
+ _setup_ftp_msg(payload_header, size, data, &msg);
+ _ftp_server->handle_message(nullptr /* mavlink */, &msg);
+ return _decode_message(&_reply_msg, ftp_msg_reply, payload_reply);
+}
+
+/// @brief Cleans up an files created on microsd during testing
+void MavlinkFtpTest::_cleanup_microsd(void)
+{
+ ::unlink(_unittest_microsd_file);
+ ::rmdir(_unittest_microsd_dir);
+}
+
+/// @brief Runs all the unit tests
+void MavlinkFtpTest::runTests(void)
+{
+ ut_run_test(_ack_test);
+ ut_run_test(_bad_opcode_test);
+ ut_run_test(_bad_datasize_test);
+ ut_run_test(_list_test);
+ ut_run_test(_list_eof_test);
+ ut_run_test(_open_badfile_test);
+ ut_run_test(_open_terminate_test);
+ ut_run_test(_terminate_badsession_test);
+ ut_run_test(_read_test);
+ ut_run_test(_read_badsession_test);
+ ut_run_test(_removedirectory_test);
+ ut_run_test(_createdirectory_test);
+ ut_run_test(_removefile_test);
+}
+
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
new file mode 100644
index 000000000..babd909da
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
@@ -0,0 +1,107 @@
+/****************************************************************************
+ *
+ * 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_test.h
+/// @author Don Gagne <don@thegagnes.com>
+
+#pragma once
+
+#include <unit_test/unit_test.h>
+#include "../mavlink_bridge_header.h"
+#include "../mavlink_ftp.h"
+
+class MavlinkFtpTest : public UnitTest
+{
+public:
+ MavlinkFtpTest();
+ virtual ~MavlinkFtpTest();
+
+ virtual void init(void);
+ virtual void cleanup(void);
+
+ virtual void runTests(void);
+
+ static void receive_message(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ static const uint8_t serverSystemId = 50; ///< System ID for server
+ static const uint8_t serverComponentId = 1; ///< Component ID for server
+ static const uint8_t serverChannel = 0; ///< Channel to send to
+
+ static const uint8_t clientSystemId = 1; ///< System ID for client
+ static const uint8_t clientComponentId = 0; ///< Component ID for client
+
+ // We don't want any of these
+ MavlinkFtpTest(const MavlinkFtpTest&);
+ MavlinkFtpTest& operator=(const MavlinkFtpTest&);
+
+private:
+ bool _ack_test(void);
+ bool _bad_opcode_test(void);
+ bool _bad_datasize_test(void);
+ bool _list_test(void);
+ bool _list_eof_test(void);
+ bool _open_badfile_test(void);
+ bool _open_terminate_test(void);
+ bool _terminate_badsession_test(void);
+ bool _read_test(void);
+ bool _read_badsession_test(void);
+ bool _removedirectory_test(void);
+ bool _createdirectory_test(void);
+ bool _removefile_test(void);
+
+ void _receive_message(const mavlink_message_t *msg);
+ void _setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, mavlink_message_t *msg);
+ bool _decode_message(const mavlink_message_t *msg, mavlink_file_transfer_protocol_t *ftp_msg, MavlinkFTP::PayloadHeader **payload);
+ bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,
+ uint8_t size,
+ const uint8_t *data,
+ mavlink_file_transfer_protocol_t *ftp_msg_reply,
+ MavlinkFTP::PayloadHeader **payload_reply);
+ void _cleanup_microsd(void);
+
+ MavlinkFTP *_ftp_server;
+
+ mavlink_message_t _reply_msg;
+
+ uint16_t _lastOutgoingSeqNumber;
+
+ struct ReadTestCase {
+ const char *file;
+ const uint16_t length;
+ };
+ static const ReadTestCase _rgReadTestCases[];
+
+ static const char _unittest_microsd_dir[];
+ static const char _unittest_microsd_file[];
+};
+
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
new file mode 100644
index 000000000..a7e68f2a3
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
@@ -0,0 +1,7 @@
+import sys
+print 'Arguments: file - ' + sys.argv[1] + ', length - ' + sys.argv[2]
+file = open(sys.argv[1], 'w')
+for i in range(int(sys.argv[2])):
+ b = bytearray([i & 0xFF])
+ file.write(b)
+file.close() \ No newline at end of file
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
new file mode 100644
index 000000000..d9c1e413a
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * 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_tests.cpp
+ */
+
+#include <systemlib/err.h>
+
+#include "mavlink_ftp_test.h"
+
+extern "C" __EXPORT int mavlink_tests_main(int argc, char *argv[]);
+
+int mavlink_tests_main(int argc, char *argv[])
+{
+ MavlinkFtpTest* test = new MavlinkFtpTest;
+
+ test->runTests();
+ test->printResults();
+
+ return 0;
+}
diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk
new file mode 100644
index 000000000..07cfce1dc
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/module.mk
@@ -0,0 +1,48 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# System state machine tests.
+#
+
+MODULE_COMMAND = mavlink_tests
+SRCS = mavlink_tests.cpp \
+ mavlink_ftp_test.cpp \
+ ../mavlink_ftp.cpp \
+ ../mavlink.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 5000
+
+EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index b63394544..fad46998e 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -87,6 +87,7 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
+#define GEOFENCE_CHECK_INTERVAL 200000
namespace navigator
{
@@ -343,7 +344,7 @@ Navigator::task_main()
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
- bool have_geofence_position_data = false;
+ static bool have_geofence_position_data = false;
/* gps updated */
if (fds[7].revents & POLLIN) {
@@ -388,17 +389,18 @@ Navigator::task_main()
if (fds[0].revents & POLLIN) {
global_position_update();
static int gposcounter = 0;
- if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS &&
- gposcounter % 10 == 0) {
- /* Geofence is checked only every 10th gpos update */
+ if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
have_geofence_position_data = true;
}
gposcounter++;
}
/* Check geofence violation */
- if (have_geofence_position_data) {
+ static hrt_abstime last_geofence_check = 0;
+ if (have_geofence_position_data && hrt_elapsed_time(&last_geofence_check) > GEOFENCE_CHECK_INTERVAL) {
bool inside = _geofence.inside(_global_pos, _gps_pos, _sensor_combined.baro_alt_meter);
+ last_geofence_check = hrt_absolute_time();
+ have_geofence_position_data = false;
if (!inside) {
/* inform other apps via the mission result */
_mission_result.geofence_violated = true;
diff --git a/src/modules/systemlib/circuit_breaker.c b/src/modules/systemlib/circuit_breaker.c
index 9e5429988..2058fa0d5 100644
--- a/src/modules/systemlib/circuit_breaker.c
+++ b/src/modules/systemlib/circuit_breaker.c
@@ -106,7 +106,7 @@ PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0);
* @max 121212
* @group Circuit Breaker
*/
-PARAM_DEFINE_INT32(CBRK_FLIGHTTERM, 0);
+PARAM_DEFINE_INT32(CBRK_FLIGHTTERM, 121212);
/**
* Circuit breaker for engine failure detection
@@ -122,6 +122,20 @@ PARAM_DEFINE_INT32(CBRK_FLIGHTTERM, 0);
*/
PARAM_DEFINE_INT32(CBRK_ENGINEFAIL, 0);
+/**
+ * Circuit breaker for gps failure detection
+ *
+ * Setting this parameter to 240024 will disable the gps failure detection.
+ * If the aircraft is in gps failure mode the gps failure flag will be
+ * set to healthy
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 240024
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_GPSFAIL, 240024);
+
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
{
int32_t val;
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index cdf60febc..17989558e 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -130,6 +130,9 @@
#include <nuttx/config.h>
#include "drivers/drv_mixer.h"
+
+#include <uORB/topics/multirotor_motor_limits.h>
+
#include "mixer_load.h"
/**
@@ -531,6 +534,9 @@ private:
float _yaw_scale;
float _idle_speed;
+ orb_advert_t _limits_pub;
+ multirotor_motor_limits_s _limits;
+
unsigned _rotor_count;
const Rotor *_rotors;
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 4b22a46d0..57e17b67d 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -36,7 +36,8 @@
*
* Multi-rotor mixers.
*/
-
+#include <uORB/uORB.h>
+#include <uORB/topics/multirotor_motor_limits.h>
#include <nuttx/config.h>
#include <sys/types.h>
@@ -302,6 +303,11 @@ MultirotorMixer::mix(float *outputs, unsigned space)
float min_out = 0.0f;
float max_out = 0.0f;
+ _limits.roll_pitch = false;
+ _limits.yaw = false;
+ _limits.throttle_upper = false;
+ _limits.throttle_lower = false;
+
/* perform initial mix pass yielding unbounded outputs, ignore yaw */
for (unsigned i = 0; i < _rotor_count; i++) {
float out = roll * _rotors[i].roll_scale +
@@ -311,6 +317,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
/* limit yaw if it causes outputs clipping */
if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) {
yaw = -out / _rotors[i].yaw_scale;
+ _limits.yaw = true;
}
/* calculate min and max output values */
@@ -332,6 +339,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
for (unsigned i = 0; i < _rotor_count; i++) {
outputs[i] = scale_in * (roll * _rotors[i].roll_scale + pitch * _rotors[i].pitch_scale) + thrust;
}
+ _limits.roll_pitch = true;
} else {
/* roll/pitch mixed without limiting, add yaw control */
@@ -344,6 +352,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
float scale_out;
if (max_out > 1.0f) {
scale_out = 1.0f / max_out;
+ _limits.throttle_upper = true;
} else {
scale_out = 1.0f;
@@ -351,9 +360,20 @@ MultirotorMixer::mix(float *outputs, unsigned space)
/* scale outputs to range _idle_speed..1, and do final limiting */
for (unsigned i = 0; i < _rotor_count; i++) {
+ if (outputs[i] < _idle_speed) {
+ _limits.throttle_lower = true;
+ }
outputs[i] = constrain(_idle_speed + (outputs[i] * (1.0f - _idle_speed) * scale_out), _idle_speed, 1.0f);
}
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ /* publish/advertise motor limits if running on FMU */
+ if (_limits_pub > 0) {
+ orb_publish(ORB_ID(multirotor_motor_limits), _limits_pub, &_limits);
+ } else {
+ _limits_pub = orb_advertise(ORB_ID(multirotor_motor_limits), &_limits);
+ }
+#endif
return _rotor_count;
}
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index e44e6cdb0..6b8d0e634 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -322,7 +322,8 @@ param_get_value_ptr(param_t param)
v = &param_info_base[param].val;
}
- if (param_type(param) == PARAM_TYPE_STRUCT) {
+ if (param_type(param) >= PARAM_TYPE_STRUCT
+ && param_type(param) <= PARAM_TYPE_STRUCT_MAX) {
result = v->p;
} else {
diff --git a/src/modules/systemlib/param/param.h b/src/modules/systemlib/param/param.h
index 084cd931a..dc73b37e9 100644
--- a/src/modules/systemlib/param/param.h
+++ b/src/modules/systemlib/param/param.h
@@ -307,7 +307,7 @@ __EXPORT int param_load_default(void);
struct param_info_s __param__##_name = { \
#_name, \
PARAM_TYPE_STRUCT + sizeof(_default), \
- .val.p = &_default; \
+ .val.p = &_default \
}
/**
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index f7d5f8737..b921865eb 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -192,6 +192,9 @@ ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
+#include "topics/multirotor_motor_limits.h"
+ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
+
#include "topics/telemetry_status.h"
ORB_DEFINE(telemetry_status_0, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_1, struct telemetry_status_s);
diff --git a/src/modules/uORB/topics/multirotor_motor_limits.h b/src/modules/uORB/topics/multirotor_motor_limits.h
new file mode 100644
index 000000000..44c51e4d9
--- /dev/null
+++ b/src/modules/uORB/topics/multirotor_motor_limits.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 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 multirotor_motor_limits.h
+ *
+ * Definition of multirotor_motor_limits topic
+ */
+
+#ifndef MULTIROTOR_MOTOR_LIMITS_H_
+#define MULTIROTOR_MOTOR_LIMITS_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Motor limits
+ */
+struct multirotor_motor_limits_s {
+ uint8_t roll_pitch : 1; // roll/pitch limit reached
+ uint8_t yaw : 1; // yaw limit reached
+ uint8_t throttle_lower : 1; // lower throttle limit reached
+ uint8_t throttle_upper : 1; // upper throttle limit reached
+ uint8_t reserved : 4;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(multirotor_motor_limits);
+
+#endif
diff --git a/src/modules/uavcan/sensors/gnss.cpp b/src/modules/uavcan/sensors/gnss.cpp
index 0d67aad47..24afe6aaf 100644
--- a/src/modules/uavcan/sensors/gnss.cpp
+++ b/src/modules/uavcan/sensors/gnss.cpp
@@ -43,8 +43,6 @@
#include <systemlib/err.h>
#include <mathlib/mathlib.h>
-#define MM_PER_CM 10 // Millimeters per centimeter
-
const char *const UavcanGnssBridge::NAME = "gnss";
UavcanGnssBridge::UavcanGnssBridge(uavcan::INode &node) :
@@ -95,9 +93,9 @@ void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavca
auto report = ::vehicle_gps_position_s();
report.timestamp_position = hrt_absolute_time();
- report.lat = msg.lat_1e7;
- report.lon = msg.lon_1e7;
- report.alt = msg.alt_1e2 * MM_PER_CM; // Convert from centimeter (1e2) to millimeters (1e3)
+ report.lat = msg.latitude_deg_1e8 / 10;
+ report.lon = msg.longitude_deg_1e8 / 10;
+ report.alt = msg.height_msl_mm;
report.timestamp_variance = report.timestamp_position;
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
index 02d1af481..be3b9461a 100644
--- a/src/modules/unit_test/unit_test.cpp
+++ b/src/modules/unit_test/unit_test.cpp
@@ -56,3 +56,8 @@ void UnitTest::printAssert(const char* msg, const char* test, const char* file,
{
warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
}
+
+void UnitTest::printCompare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
+{
+ warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
+}
diff --git a/src/modules/unit_test/unit_test.h b/src/modules/unit_test/unit_test.h
index 32eb8c308..1a5489709 100644
--- a/src/modules/unit_test/unit_test.h
+++ b/src/modules/unit_test/unit_test.h
@@ -52,11 +52,15 @@ INLINE_GLOBAL(const char*, mu_last_test)
UnitTest();
virtual ~UnitTest();
+
+ virtual void init(void) { };
+ virtual void cleanup(void) { };
virtual void runTests(void) = 0;
void printResults(void);
void printAssert(const char* msg, const char* test, const char* file, int line);
+ void printCompare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line);
#define ut_assert(message, test) \
do { \
@@ -68,10 +72,23 @@ INLINE_GLOBAL(const char*, mu_last_test)
} \
} while (0)
+#define ut_compare(message, v1, v2) \
+ do { \
+ int _v1 = v1; \
+ int _v2 = v2; \
+ if (_v1 != _v2) { \
+ printCompare(message, #v1, _v1, #v2, _v2, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ mu_assertion()++; \
+ } \
+ } while (0)
+
#define ut_run_test(test) \
do { \
warnx("RUNNING TEST: %s", #test); \
mu_tests_run()++; \
+ init(); \
if (!test()) { \
warnx("TEST FAILED: %s", #test); \
mu_tests_failed()++; \
@@ -79,6 +96,7 @@ INLINE_GLOBAL(const char*, mu_last_test)
warnx("TEST PASSED: %s", #test); \
mu_tests_passed()++; \
} \
+ cleanup(); \
} while (0)
};
diff --git a/uavcan b/uavcan
-Subproject c4c14c60fbbd9acd281ee97d5bb2a4027d0ae2d
+Subproject 286adbcc56c4b093143b647ec7546abb149cd53