aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp5
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c125
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp27
-rw-r--r--src/modules/mavlink/mavlink_ftp.h11
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp57
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h2
6 files changed, 83 insertions, 144 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 81e25da99..23167eef4 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -211,6 +211,7 @@ private:
float max_climb_rate;
float climbout_diff;
float heightrate_p;
+ float heightrate_ff;
float speedrate_p;
float throttle_damp;
float integrator_gain;
@@ -256,6 +257,7 @@ private:
param_t max_climb_rate;
param_t climbout_diff;
param_t heightrate_p;
+ param_t heightrate_ff;
param_t speedrate_p;
param_t throttle_damp;
param_t integrator_gain;
@@ -495,6 +497,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
+ _parameter_handles.heightrate_ff = param_find("FW_T_HRATE_FF");
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
/* fetch initial parameter values */
@@ -564,6 +567,7 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff));
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
+ param_get(_parameter_handles.heightrate_ff, &(_parameters.heightrate_ff));
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle));
@@ -601,6 +605,7 @@ FixedwingPositionControl::parameters_update()
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
_tecs.set_heightrate_p(_parameters.heightrate_p);
+ _tecs.set_heightrate_ff(_parameters.heightrate_ff);
_tecs.set_speedrate_p(_parameters.speedrate_p);
/* sanity check parameters */
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 890ab3bad..847ecbb5c 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -131,8 +131,8 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f);
/**
* Throttle limit max
*
- * This is the maximum throttle % that can be used by the controller.
- * For overpowered aircraft, this should be reduced to a value that
+ * This is the maximum throttle % that can be used by the controller.
+ * For overpowered aircraft, this should be reduced to a value that
* provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
*
* @group L1 Control
@@ -142,10 +142,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
/**
* Throttle limit min
*
- * This is the minimum throttle % that can be used by the controller.
- * For electric aircraft this will normally be set to zero, but can be set
- * to a small non-zero value if a folding prop is fitted to prevent the
- * prop from folding and unfolding repeatedly in-flight or to provide
+ * This is the minimum throttle % that can be used by the controller.
+ * For electric aircraft this will normally be set to zero, but can be set
+ * to a small non-zero value if a folding prop is fitted to prevent the
+ * prop from folding and unfolding repeatedly in-flight or to provide
* some aerodynamic drag from a turning prop to improve the descent rate.
*
* For aircraft with internal combustion engine this parameter should be set
@@ -158,7 +158,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Throttle limit value before flare
*
- * This throttle value will be set as throttle limit at FW_LND_TLALT,
+ * This throttle value will be set as throttle limit at FW_LND_TLALT,
* before arcraft will flare.
*
* @group L1 Control
@@ -180,17 +180,17 @@ PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 25.0f);
/**
* Maximum climb rate
*
- * This is the best climb rate that the aircraft can achieve with
- * the throttle set to THR_MAX and the airspeed set to the
- * default value. For electric aircraft make sure this number can be
- * achieved towards the end of flight when the battery voltage has reduced.
- * The setting of this parameter can be checked by commanding a positive
- * altitude change of 100m in loiter, RTL or guided mode. If the throttle
- * required to climb is close to THR_MAX and the aircraft is maintaining
- * airspeed, then this parameter is set correctly. If the airspeed starts
- * to reduce, then the parameter is set to high, and if the throttle
- * demand required to climb and maintain speed is noticeably less than
- * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
+ * This is the best climb rate that the aircraft can achieve with
+ * the throttle set to THR_MAX and the airspeed set to the
+ * default value. For electric aircraft make sure this number can be
+ * achieved towards the end of flight when the battery voltage has reduced.
+ * The setting of this parameter can be checked by commanding a positive
+ * altitude change of 100m in loiter, RTL or guided mode. If the throttle
+ * required to climb is close to THR_MAX and the aircraft is maintaining
+ * airspeed, then this parameter is set correctly. If the airspeed starts
+ * to reduce, then the parameter is set to high, and if the throttle
+ * demand required to climb and maintain speed is noticeably less than
+ * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
* FW_THR_MAX reduced.
*
* @group L1 Control
@@ -200,8 +200,8 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
/**
* Minimum descent rate
*
- * This is the sink rate of the aircraft with the throttle
- * set to THR_MIN and flown at the same airspeed as used
+ * This is the sink rate of the aircraft with the throttle
+ * set to THR_MIN and flown at the same airspeed as used
* to measure FW_T_CLMB_MAX.
*
* @group Fixed Wing TECS
@@ -211,10 +211,10 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
/**
* Maximum descent rate
*
- * This sets the maximum descent rate that the controller will use.
- * If this value is too large, the aircraft can over-speed on descent.
- * This should be set to a value that can be achieved without
- * exceeding the lower pitch angle limit and without over-speeding
+ * This sets the maximum descent rate that the controller will use.
+ * If this value is too large, the aircraft can over-speed on descent.
+ * This should be set to a value that can be achieved without
+ * exceeding the lower pitch angle limit and without over-speeding
* the aircraft.
*
* @group Fixed Wing TECS
@@ -224,7 +224,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
/**
* TECS time constant
*
- * This is the time constant of the TECS control algorithm (in seconds).
+ * This is the time constant of the TECS control algorithm (in seconds).
* Smaller values make it faster to respond, larger values make it slower
* to respond.
*
@@ -235,7 +235,7 @@ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
/**
* TECS Throttle time constant
*
- * This is the time constant of the TECS throttle control algorithm (in seconds).
+ * This is the time constant of the TECS throttle control algorithm (in seconds).
* Smaller values make it faster to respond, larger values make it slower
* to respond.
*
@@ -246,7 +246,7 @@ PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
/**
* Throttle damping factor
*
- * This is the damping gain for the throttle demand loop.
+ * This is the damping gain for the throttle demand loop.
* Increase to add damping to correct for oscillations in speed and height.
*
* @group Fixed Wing TECS
@@ -256,9 +256,9 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
/**
* Integrator gain
*
- * This is the integrator gain on the control loop.
- * Increasing this gain increases the speed at which speed
- * and height offsets are trimmed out, but reduces damping and
+ * This is the integrator gain on the control loop.
+ * Increasing this gain increases the speed at which speed
+ * and height offsets are trimmed out, but reduces damping and
* increases overshoot.
*
* @group Fixed Wing TECS
@@ -269,9 +269,9 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
* Maximum vertical acceleration
*
* This is the maximum vertical acceleration (in metres/second square)
- * either up or down that the controller will use to correct speed
- * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
- * allows for reasonably aggressive pitch changes if required to recover
+ * either up or down that the controller will use to correct speed
+ * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
+ * allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
*
* @group Fixed Wing TECS
@@ -281,10 +281,10 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
/**
* Complementary filter "omega" parameter for height
*
- * This is the cross-over frequency (in radians/second) of the complementary
- * filter used to fuse vertical acceleration and barometric height to obtain
- * an estimate of height rate and height. Increasing this frequency weights
- * the solution more towards use of the barometer, whilst reducing it weights
+ * This is the cross-over frequency (in radians/second) of the complementary
+ * filter used to fuse vertical acceleration and barometric height to obtain
+ * an estimate of height rate and height. Increasing this frequency weights
+ * the solution more towards use of the barometer, whilst reducing it weights
* the solution more towards use of the accelerometer data.
*
* @group Fixed Wing TECS
@@ -294,10 +294,10 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
/**
* Complementary filter "omega" parameter for speed
*
- * This is the cross-over frequency (in radians/second) of the complementary
- * filter used to fuse longitudinal acceleration and airspeed to obtain an
+ * This is the cross-over frequency (in radians/second) of the complementary
+ * filter used to fuse longitudinal acceleration and airspeed to obtain an
* improved airspeed estimate. Increasing this frequency weights the solution
- * more towards use of the arispeed sensor, whilst reducing it weights the
+ * more towards use of the arispeed sensor, whilst reducing it weights the
* solution more towards use of the accelerometer data.
*
* @group Fixed Wing TECS
@@ -307,13 +307,13 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
/**
* Roll -> Throttle feedforward
*
- * Increasing this gain turn increases the amount of throttle that will
- * be used to compensate for the additional drag created by turning.
- * Ideally this should be set to approximately 10 x the extra sink rate
- * in m/s created by a 45 degree bank turn. Increase this gain if
- * the aircraft initially loses energy in turns and reduce if the
- * aircraft initially gains energy in turns. Efficient high aspect-ratio
- * aircraft (eg powered sailplanes) can use a lower value, whereas
+ * Increasing this gain turn increases the amount of throttle that will
+ * be used to compensate for the additional drag created by turning.
+ * Ideally this should be set to approximately 10 x the extra sink rate
+ * in m/s created by a 45 degree bank turn. Increase this gain if
+ * the aircraft initially loses energy in turns and reduce if the
+ * aircraft initially gains energy in turns. Efficient high aspect-ratio
+ * aircraft (eg powered sailplanes) can use a lower value, whereas
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
*
* @group Fixed Wing TECS
@@ -323,15 +323,15 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
/**
* Speed <--> Altitude priority
*
- * This parameter adjusts the amount of weighting that the pitch control
- * applies to speed vs height errors. Setting it to 0.0 will cause the
- * pitch control to control height and ignore speed errors. This will
- * normally improve height accuracy but give larger airspeed errors.
- * Setting it to 2.0 will cause the pitch control loop to control speed
- * and ignore height errors. This will normally reduce airspeed errors,
- * but give larger height errors. The default value of 1.0 allows the pitch
- * control to simultaneously control height and speed.
- * Note to Glider Pilots - set this parameter to 2.0 (The glider will
+ * This parameter adjusts the amount of weighting that the pitch control
+ * applies to speed vs height errors. Setting it to 0.0 will cause the
+ * pitch control to control height and ignore speed errors. This will
+ * normally improve height accuracy but give larger airspeed errors.
+ * Setting it to 2.0 will cause the pitch control loop to control speed
+ * and ignore height errors. This will normally reduce airspeed errors,
+ * but give larger height errors. The default value of 1.0 allows the pitch
+ * control to simultaneously control height and speed.
+ * Note to Glider Pilots - set this parameter to 2.0 (The glider will
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
*
* @group Fixed Wing TECS
@@ -341,9 +341,9 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
/**
* Pitch damping factor
*
- * This is the damping gain for the pitch demand loop. Increase to add
- * damping to correct for oscillations in height. The default value of 0.0
- * will work well provided the pitch to servo controller has been tuned
+ * This is the damping gain for the pitch demand loop. Increase to add
+ * damping to correct for oscillations in height. The default value of 0.0
+ * will work well provided the pitch to servo controller has been tuned
* properly.
*
* @group Fixed Wing TECS
@@ -358,6 +358,13 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
/**
+ * Height rate FF factor
+ *
+ * @group Fixed Wing TECS
+ */
+PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f);
+
+/**
* Speed rate P factor
*
* @group Fixed Wing TECS
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 72ede8797..64206ac54 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -34,7 +34,6 @@
/// @file mavlink_ftp.cpp
/// @author px4dev, Don Gagne <don@thegagnes.com>
-#include <crc32.h>
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
@@ -161,13 +160,6 @@ MavlinkFTP::_process_request(Request *req)
goto out;
}
- // check request CRC to make sure this is one of ours
- if (_payload_crc32(payload) != payload->crc32) {
- errorCode = kErrCrc;
- goto out;
- warnx("ftp: bad crc");
- }
-
#ifdef MAVLINK_FTP_DEBUG
printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset);
#endif
@@ -224,12 +216,14 @@ MavlinkFTP::_process_request(Request *req)
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 {
warnx("FTP: nak %u", errorCode);
+ payload->req_opcode = payload->opcode;
payload->opcode = kRspNak;
payload->size = 1;
payload->data[0] = errorCode;
@@ -254,8 +248,6 @@ MavlinkFTP::_reply(Request *req)
payload->seqNumber = payload->seqNumber + 1;
- payload->crc32 = _payload_crc32(payload);
-
mavlink_message_t msg;
msg.checksum = 0;
#ifndef MAVLINK_FTP_UNIT_TEST
@@ -645,18 +637,3 @@ MavlinkFTP::_return_request(Request *req)
_unlock_request_queue();
}
-/// @brief Returns the 32 bit CRC for the payload, crc32 and padding members are set to 0 for calculation.
-uint32_t
-MavlinkFTP::_payload_crc32(PayloadHeader *payload)
-{
- // We calculate CRC with crc and padding set to 0.
- uint32_t saveCRC = payload->crc32;
- payload->crc32 = 0;
- payload->padding[0] = 0;
- payload->padding[1] = 0;
- payload->padding[2] = 0;
- uint32_t retCRC = crc32((const uint8_t*)payload, payload->size + sizeof(PayloadHeader));
- payload->crc32 = saveCRC;
-
- return retCRC;
-}
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index b4cc154d1..4892e548c 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -76,8 +76,8 @@ public:
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]; ///< 32 bit aligment padding
- uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0
+ 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
};
@@ -97,7 +97,7 @@ public:
kCmdCreateDirectory, ///< Creates directory at <path>
kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
- kRspAck, ///< Ack response
+ kRspAck = 128, ///< Ack response
kRspNak ///< Nak response
};
@@ -111,8 +111,7 @@ public:
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
- kErrCrc ///< CRC on Payload is incorrect
+ kErrUnknownCommand ///< Unknown command opcode
};
private:
@@ -134,8 +133,6 @@ private:
void _lock_request_queue(void);
void _unlock_request_queue(void);
- uint32_t _payload_crc32(PayloadHeader *hdr);
-
char *_data_as_cstring(PayloadHeader* payload);
static void _worker_trampoline(void *arg);
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
index ebfce6d74..3616db237 100644
--- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
@@ -44,9 +44,9 @@
/// @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_234.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_235.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
- { "/etc/unit_test_data/mavlink_tests/test_236.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
+ { "/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";
@@ -105,33 +105,6 @@ bool MavlinkFtpTest::_ack_test(void)
return true;
}
-/// @brief Tests for correct response to a message sent with an invalid CRC.
-bool MavlinkFtpTest::_bad_crc_test(void)
-{
- mavlink_message_t msg;
- MavlinkFTP::PayloadHeader payload;
- mavlink_file_transfer_protocol_t ftp_msg;
- MavlinkFTP::PayloadHeader *reply;
-
- payload.opcode = MavlinkFTP::kCmdNone;
-
- _setup_ftp_msg(&payload, 0, nullptr, &msg);
-
- ((MavlinkFTP::PayloadHeader*)((mavlink_file_transfer_protocol_t*)msg.payload64)->payload)->crc32++;
-
- _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::kErrCrc);
-
- return true;
-}
-
/// @brief Tests for correct response to an invalid opcpde.
bool MavlinkFtpTest::_bad_opcode_test(void)
{
@@ -191,7 +164,7 @@ bool MavlinkFtpTest::_list_test(void)
mavlink_file_transfer_protocol_t ftp_msg;
MavlinkFTP::PayloadHeader *reply;
- char response1[] = "D.|Dempty_dir|Ftest_234.data\t234|Ftest_235.data\t235|Ftest_236.data\t236";
+ char response1[] = "D.|Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
char response2[] = "Ddev|Detc|Dfs|Dobj";
struct _testCase {
@@ -690,9 +663,6 @@ bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlin
*payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
- // Make sure we have a good CRC
- ut_compare("Incoming CRC mismatch", (*payload)->crc32, _payload_crc32((*payload)));
-
// Make sure we have a good sequence number
ut_compare("Sequence number mismatch", (*payload)->seqNumber, _lastOutgoingSeqNumber + 1);
@@ -702,21 +672,6 @@ bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlin
return true;
}
-/// @brief Returns the 32 bit CRC for the payload, crc32 and padding are set to 0 for calculation.
-uint32_t MavlinkFtpTest::_payload_crc32(struct MavlinkFTP::PayloadHeader *payload)
-{
- // We calculate CRC with crc and padding set to 0.
- uint32_t saveCRC = payload->crc32;
- payload->crc32 = 0;
- payload->padding[0] = 0;
- payload->padding[1] = 0;
- payload->padding[2] = 0;
- uint32_t retCRC = crc32((const uint8_t*)payload, payload->size + sizeof(MavlinkFTP::PayloadHeader));
- payload->crc32 = saveCRC;
-
- return retCRC;
-}
-
/// @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
@@ -734,7 +689,8 @@ void MavlinkFtpTest::_setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, /
memcpy(payload->data, data, size);
}
- payload->crc32 = _payload_crc32(payload);
+ payload->padding[0] = 0;
+ payload->padding[1] = 0;
msg->checksum = 0;
mavlink_msg_file_transfer_protocol_pack(clientSystemId, // Sender system id
@@ -771,7 +727,6 @@ void MavlinkFtpTest::_cleanup_microsd(void)
void MavlinkFtpTest::runTests(void)
{
ut_run_test(_ack_test);
- ut_run_test(_bad_crc_test);
ut_run_test(_bad_opcode_test);
ut_run_test(_bad_datasize_test);
ut_run_test(_list_test);
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
index bbb095a08..babd909da 100644
--- a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
@@ -66,7 +66,6 @@ public:
private:
bool _ack_test(void);
- bool _bad_crc_test(void);
bool _bad_opcode_test(void);
bool _bad_datasize_test(void);
bool _list_test(void);
@@ -81,7 +80,6 @@ private:
bool _removefile_test(void);
void _receive_message(const mavlink_message_t *msg);
- uint32_t _payload_crc32(struct MavlinkFTP::PayloadHeader *payload);
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,