forked from Archive/PX4-Autopilot
clang-tidy modernize-redundant-void-arg
This commit is contained in:
parent
e927f3e040
commit
6631e72d6f
|
@ -1,7 +1,9 @@
|
|||
Checks: '-*,readability-braces-around-statements,
|
||||
modernize-use-nullptr'
|
||||
modernize-use-nullptr,
|
||||
modernize-redundant-void-arg'
|
||||
WarningsAsErrors: 'readability-braces-around-statements,
|
||||
modernize-use-nullptr'
|
||||
modernize-use-nullptr,
|
||||
modernize-redundant-void-arg'
|
||||
HeaderFilterRegex: '*.h, *.hpp'
|
||||
AnalyzeTemporaryDtors: false
|
||||
CheckOptions:
|
||||
|
|
|
@ -356,7 +356,7 @@ RingBuffer::get(double &val)
|
|||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::space(void)
|
||||
RingBuffer::space()
|
||||
{
|
||||
unsigned tail, head;
|
||||
|
||||
|
@ -377,7 +377,7 @@ RingBuffer::space(void)
|
|||
}
|
||||
|
||||
unsigned
|
||||
RingBuffer::count(void)
|
||||
RingBuffer::count()
|
||||
{
|
||||
/*
|
||||
* Note that due to the conservative nature of space(), this may
|
||||
|
|
|
@ -160,7 +160,7 @@ private:
|
|||
/**
|
||||
* Worker task: main GPS thread that configures the GPS and parses incoming data, always running
|
||||
*/
|
||||
void task_main(void);
|
||||
void task_main();
|
||||
|
||||
/**
|
||||
* Set the baudrate of the UART to the GPS
|
||||
|
|
|
@ -158,10 +158,10 @@ private:
|
|||
static const GPIOConfig _gpio_tab[];
|
||||
static const unsigned _ngpio;
|
||||
|
||||
void gpio_reset(void);
|
||||
void gpio_reset();
|
||||
void gpio_set_function(uint32_t gpios, int function);
|
||||
void gpio_write(uint32_t gpios, int function);
|
||||
uint32_t gpio_read(void);
|
||||
uint32_t gpio_read();
|
||||
int gpio_ioctl(device::file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
};
|
||||
|
@ -928,7 +928,7 @@ hil_new_mode(PortMode new_mode)
|
|||
}
|
||||
|
||||
int
|
||||
test(void)
|
||||
test()
|
||||
{
|
||||
int fd;
|
||||
|
||||
|
|
|
@ -12,20 +12,20 @@ extern "C" __EXPORT int sf0x_tests_main(int argc, char *argv[]);
|
|||
class SF0XTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool sf0xTest();
|
||||
};
|
||||
|
||||
bool SF0XTest::run_tests(void)
|
||||
bool SF0XTest::run_tests()
|
||||
{
|
||||
ut_run_test(sf0xTest);
|
||||
|
||||
return (_tests_failed == 0);
|
||||
}
|
||||
|
||||
bool SF0XTest::sf0xTest(void)
|
||||
bool SF0XTest::sf0xTest()
|
||||
{
|
||||
const char _LINE_MAX = 20;
|
||||
//char _linebuf[_LINE_MAX];
|
||||
|
|
|
@ -115,7 +115,7 @@ struct ParameterHandles {
|
|||
|
||||
|
||||
/* functions */
|
||||
static void usage(void);
|
||||
static void usage();
|
||||
static void update_params(ParameterHandles ¶m_handles, Parameters ¶ms, bool &got_changes);
|
||||
static bool get_params(ParameterHandles ¶m_handles, Parameters ¶ms);
|
||||
|
||||
|
|
|
@ -2854,7 +2854,7 @@ bool AttPosEKF::FilterHealthy()
|
|||
return true;
|
||||
}
|
||||
|
||||
void AttPosEKF::ResetPosition(void)
|
||||
void AttPosEKF::ResetPosition()
|
||||
{
|
||||
if (staticMode) {
|
||||
states[7] = 0;
|
||||
|
@ -2877,7 +2877,7 @@ void AttPosEKF::ResetPosition(void)
|
|||
P[8][8] = P[7][7];
|
||||
}
|
||||
|
||||
void AttPosEKF::ResetHeight(void)
|
||||
void AttPosEKF::ResetHeight()
|
||||
{
|
||||
// write to the state vector
|
||||
states[9] = -hgtMea;
|
||||
|
@ -2892,7 +2892,7 @@ void AttPosEKF::ResetHeight(void)
|
|||
P[6][6] = sq(0.7f);
|
||||
}
|
||||
|
||||
void AttPosEKF::ResetVelocity(void)
|
||||
void AttPosEKF::ResetVelocity()
|
||||
{
|
||||
if (staticMode) {
|
||||
states[4] = 0.0f;
|
||||
|
|
|
@ -74,12 +74,12 @@ void ekf_debug(const char *fmt, ...) { while(0){} }
|
|||
/* we don't want to pull in the standard lib just to swap two floats */
|
||||
void swap_var(float &d1, float &d2);
|
||||
|
||||
float Vector3f::length(void) const
|
||||
float Vector3f::length() const
|
||||
{
|
||||
return sqrt(x*x + y*y + z*z);
|
||||
}
|
||||
|
||||
void Vector3f::zero(void)
|
||||
void Vector3f::zero()
|
||||
{
|
||||
x = 0.0f;
|
||||
y = 0.0f;
|
||||
|
|
|
@ -171,7 +171,7 @@ void TECS::_update_speed(float airspeed_demand, float indicated_airspeed,
|
|||
_update_speed_last_usec = now;
|
||||
}
|
||||
|
||||
void TECS::_update_speed_demand(void)
|
||||
void TECS::_update_speed_demand()
|
||||
{
|
||||
// Set the airspeed demand to the minimum value if an underspeed condition exists
|
||||
// or a bad descent condition exists
|
||||
|
@ -276,7 +276,7 @@ void TECS::_update_height_demand(float demand, float state)
|
|||
//warnx("_hgt_rate_dem: %.4f, _hgt_dem_adj %.4f", _hgt_rate_dem, _hgt_dem_adj);
|
||||
}
|
||||
|
||||
void TECS::_detect_underspeed(void)
|
||||
void TECS::_detect_underspeed()
|
||||
{
|
||||
if (!_detect_underspeed_enabled) {
|
||||
_underspeed = false;
|
||||
|
@ -291,7 +291,7 @@ void TECS::_detect_underspeed(void)
|
|||
}
|
||||
}
|
||||
|
||||
void TECS::_update_energies(void)
|
||||
void TECS::_update_energies()
|
||||
{
|
||||
// Calculate specific energy demands
|
||||
_SPE_dem = _hgt_dem_adj * CONSTANTS_ONE_G;
|
||||
|
@ -393,7 +393,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM
|
|||
}
|
||||
}
|
||||
|
||||
void TECS::_detect_bad_descent(void)
|
||||
void TECS::_detect_bad_descent()
|
||||
{
|
||||
// Detect a demanded airspeed too high for the aircraft to achieve. This will be
|
||||
// evident by the the following conditions:
|
||||
|
@ -421,7 +421,7 @@ void TECS::_detect_bad_descent(void)
|
|||
_badDescent = false;
|
||||
}
|
||||
|
||||
void TECS::_update_pitch(void)
|
||||
void TECS::_update_pitch()
|
||||
{
|
||||
// Calculate Speed/Height Control Weighting
|
||||
// This is used to determine how the pitch control prioritises speed and height control
|
||||
|
@ -544,7 +544,7 @@ void TECS::_initialise_states(float pitch, float throttle_cruise, float baro_alt
|
|||
_states_initalized = true;
|
||||
}
|
||||
|
||||
void TECS::_update_STE_rate_lim(void)
|
||||
void TECS::_update_STE_rate_lim()
|
||||
{
|
||||
// Calculate Specific Total Energy Rate Limits
|
||||
// This is a trivial calculation at the moment but will get bigger once we start adding altitude effects
|
||||
|
|
|
@ -24,7 +24,7 @@ extern "C" __EXPORT int rc_tests_main(int argc, char *argv[]);
|
|||
class RCTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool dsmTest(const char *filepath, unsigned expected_chancount, unsigned expected_dropcount, unsigned chan0);
|
||||
|
@ -35,7 +35,7 @@ private:
|
|||
bool sumdTest();
|
||||
};
|
||||
|
||||
bool RCTest::run_tests(void)
|
||||
bool RCTest::run_tests()
|
||||
{
|
||||
ut_run_test(dsmTest10Ch);
|
||||
ut_run_test(dsmTest12Ch);
|
||||
|
@ -131,7 +131,7 @@ bool RCTest::dsmTest(const char *filepath, unsigned expected_chancount, unsigned
|
|||
return true;
|
||||
}
|
||||
|
||||
bool RCTest::sbus2Test(void)
|
||||
bool RCTest::sbus2Test()
|
||||
{
|
||||
const char *filepath = TEST_DATA_PATH "sbus2_r7008SB.txt";
|
||||
|
||||
|
@ -212,7 +212,7 @@ bool RCTest::sbus2Test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool RCTest::st24Test(void)
|
||||
bool RCTest::st24Test()
|
||||
{
|
||||
const char *filepath = TEST_DATA_PATH "st24_data.txt";
|
||||
|
||||
|
@ -273,7 +273,7 @@ bool RCTest::st24Test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool RCTest::sumdTest(void)
|
||||
bool RCTest::sumdTest()
|
||||
{
|
||||
const char *filepath = TEST_DATA_PATH "sumd_data.txt";
|
||||
|
||||
|
|
|
@ -793,7 +793,7 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub,
|
|||
return result;
|
||||
}
|
||||
|
||||
int calibrate_cancel_subscribe(void)
|
||||
int calibrate_cancel_subscribe()
|
||||
{
|
||||
return orb_subscribe(ORB_ID(vehicle_command));
|
||||
}
|
||||
|
|
|
@ -49,7 +49,7 @@ public:
|
|||
StateMachineHelperTest();
|
||||
virtual ~StateMachineHelperTest();
|
||||
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool armingStateTransitionTest();
|
||||
|
@ -63,7 +63,7 @@ StateMachineHelperTest::StateMachineHelperTest() {
|
|||
StateMachineHelperTest::~StateMachineHelperTest() {
|
||||
}
|
||||
|
||||
bool StateMachineHelperTest::armingStateTransitionTest(void)
|
||||
bool StateMachineHelperTest::armingStateTransitionTest()
|
||||
{
|
||||
// These are the critical values from vehicle_status_s and actuator_armed_s which must be primed
|
||||
// to simulate machine state prior to testing an arming state transition. This structure is also
|
||||
|
@ -311,7 +311,7 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool StateMachineHelperTest::mainStateTransitionTest(void)
|
||||
bool StateMachineHelperTest::mainStateTransitionTest()
|
||||
{
|
||||
// This structure represent a single test case for testing Main State transitions.
|
||||
typedef struct {
|
||||
|
@ -475,7 +475,7 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool StateMachineHelperTest::isSafeTest(void)
|
||||
bool StateMachineHelperTest::isSafeTest()
|
||||
{
|
||||
struct vehicle_status_s current_state = {};
|
||||
struct safety_s safety = {};
|
||||
|
@ -514,7 +514,7 @@ bool StateMachineHelperTest::isSafeTest(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool StateMachineHelperTest::run_tests(void)
|
||||
bool StateMachineHelperTest::run_tests()
|
||||
{
|
||||
ut_run_test(armingStateTransitionTest);
|
||||
ut_run_test(mainStateTransitionTest);
|
||||
|
|
|
@ -64,19 +64,19 @@ MavlinkFTP::~MavlinkFTP()
|
|||
}
|
||||
|
||||
const char *
|
||||
MavlinkFTP::get_name(void) const
|
||||
MavlinkFTP::get_name() const
|
||||
{
|
||||
return "MAVLINK_FTP";
|
||||
}
|
||||
|
||||
uint16_t
|
||||
MavlinkFTP::get_id(void)
|
||||
MavlinkFTP::get_id()
|
||||
{
|
||||
return MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL;
|
||||
}
|
||||
|
||||
unsigned
|
||||
MavlinkFTP::get_size(void)
|
||||
MavlinkFTP::get_size()
|
||||
{
|
||||
if (_session_info.stream_download) {
|
||||
return MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
@ -102,7 +102,7 @@ MavlinkFTP::set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, void *worker_da
|
|||
#endif
|
||||
|
||||
uint8_t
|
||||
MavlinkFTP::_getServerSystemId(void)
|
||||
MavlinkFTP::_getServerSystemId()
|
||||
{
|
||||
#ifdef MAVLINK_FTP_UNIT_TEST
|
||||
// We use fake ids when unit testing
|
||||
|
@ -114,7 +114,7 @@ MavlinkFTP::_getServerSystemId(void)
|
|||
}
|
||||
|
||||
uint8_t
|
||||
MavlinkFTP::_getServerComponentId(void)
|
||||
MavlinkFTP::_getServerComponentId()
|
||||
{
|
||||
#ifdef MAVLINK_FTP_UNIT_TEST
|
||||
// We use fake ids when unit testing
|
||||
|
@ -126,7 +126,7 @@ MavlinkFTP::_getServerComponentId(void)
|
|||
}
|
||||
|
||||
uint8_t
|
||||
MavlinkFTP::_getServerChannel(void)
|
||||
MavlinkFTP::_getServerChannel()
|
||||
{
|
||||
#ifdef MAVLINK_FTP_UNIT_TEST
|
||||
// We use fake ids when unit testing
|
||||
|
|
|
@ -119,21 +119,21 @@ MavlinkLogHandler::handle_message(const mavlink_message_t *msg)
|
|||
|
||||
//-------------------------------------------------------------------
|
||||
const char *
|
||||
MavlinkLogHandler::get_name(void) const
|
||||
MavlinkLogHandler::get_name() const
|
||||
{
|
||||
return "MAVLINK_LOG_HANDLER";
|
||||
}
|
||||
|
||||
//-------------------------------------------------------------------
|
||||
uint16_t
|
||||
MavlinkLogHandler::get_id(void)
|
||||
MavlinkLogHandler::get_id()
|
||||
{
|
||||
return MAVLINK_MSG_ID_LOG_ENTRY;
|
||||
}
|
||||
|
||||
//-------------------------------------------------------------------
|
||||
unsigned
|
||||
MavlinkLogHandler::get_size(void)
|
||||
MavlinkLogHandler::get_size()
|
||||
{
|
||||
//-- Sending Log Entries
|
||||
if (_pLogHandlerHelper && _pLogHandlerHelper->current_status == LogListHelper::LOG_HANDLER_LISTING) {
|
||||
|
|
|
@ -170,7 +170,7 @@ mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
|
|||
}
|
||||
}
|
||||
|
||||
static void usage(void);
|
||||
static void usage();
|
||||
|
||||
bool Mavlink::_boot_complete = false;
|
||||
bool Mavlink::_config_link_on = false;
|
||||
|
@ -553,7 +553,7 @@ Mavlink::get_channel()
|
|||
return _channel;
|
||||
}
|
||||
|
||||
void Mavlink::mavlink_update_system(void)
|
||||
void Mavlink::mavlink_update_system()
|
||||
{
|
||||
if (!_param_initialized) {
|
||||
_param_system_id = param_find("MAV_SYS_ID");
|
||||
|
|
|
@ -1154,7 +1154,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
|
|||
}
|
||||
|
||||
|
||||
void MavlinkMissionManager::check_active_mission(void)
|
||||
void MavlinkMissionManager::check_active_mission()
|
||||
{
|
||||
if (!(_my_dataman_id == _dataman_id)) {
|
||||
if (_verbose) { warnx("WPM: New mission detected (possibly over different Mavlink instance) Updating"); }
|
||||
|
|
|
@ -71,7 +71,7 @@ MavlinkFtpTest::~MavlinkFtpTest()
|
|||
}
|
||||
|
||||
/// @brief Called before every test to initialize the FTP Server.
|
||||
void MavlinkFtpTest::_init(void)
|
||||
void MavlinkFtpTest::_init()
|
||||
{
|
||||
_expected_seq_number = 0;
|
||||
_ftp_server = new MavlinkFTP(nullptr);
|
||||
|
@ -81,7 +81,7 @@ void MavlinkFtpTest::_init(void)
|
|||
}
|
||||
|
||||
/// @brief Called after every test to take down the FTP Server.
|
||||
void MavlinkFtpTest::_cleanup(void)
|
||||
void MavlinkFtpTest::_cleanup()
|
||||
{
|
||||
delete _ftp_server;
|
||||
|
||||
|
@ -89,7 +89,7 @@ void MavlinkFtpTest::_cleanup(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct behavior of an Ack response.
|
||||
bool MavlinkFtpTest::_ack_test(void)
|
||||
bool MavlinkFtpTest::_ack_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -112,7 +112,7 @@ bool MavlinkFtpTest::_ack_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct response to an invalid opcpde.
|
||||
bool MavlinkFtpTest::_bad_opcode_test(void)
|
||||
bool MavlinkFtpTest::_bad_opcode_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -136,7 +136,7 @@ bool MavlinkFtpTest::_bad_opcode_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to a payload which an invalid data size field.
|
||||
bool MavlinkFtpTest::_bad_datasize_test(void)
|
||||
bool MavlinkFtpTest::_bad_datasize_test()
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
|
@ -163,7 +163,7 @@ bool MavlinkFtpTest::_bad_datasize_test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MavlinkFtpTest::_list_test(void)
|
||||
bool MavlinkFtpTest::_list_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -244,7 +244,7 @@ bool MavlinkFtpTest::_list_test(void)
|
|||
|
||||
/// @brief Tests for correct response 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)
|
||||
bool MavlinkFtpTest::_list_eof_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -270,7 +270,7 @@ bool MavlinkFtpTest::_list_eof_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct response to an Open command on a file which does not exist.
|
||||
bool MavlinkFtpTest::_open_badfile_test(void)
|
||||
bool MavlinkFtpTest::_open_badfile_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -296,7 +296,7 @@ bool MavlinkFtpTest::_open_badfile_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
|
||||
bool MavlinkFtpTest::_open_terminate_test(void)
|
||||
bool MavlinkFtpTest::_open_terminate_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -345,7 +345,7 @@ bool MavlinkFtpTest::_open_terminate_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to a Terminate command on an invalid session.
|
||||
bool MavlinkFtpTest::_terminate_badsession_test(void)
|
||||
bool MavlinkFtpTest::_terminate_badsession_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -386,7 +386,7 @@ bool MavlinkFtpTest::_terminate_badsession_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to a Read command on an open session.
|
||||
bool MavlinkFtpTest::_read_test(void)
|
||||
bool MavlinkFtpTest::_read_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -497,7 +497,7 @@ bool MavlinkFtpTest::_read_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to a Read command on an open session.
|
||||
bool MavlinkFtpTest::_burst_test(void)
|
||||
bool MavlinkFtpTest::_burst_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -584,7 +584,7 @@ bool MavlinkFtpTest::_burst_test(void)
|
|||
}
|
||||
|
||||
/// @brief Tests for correct reponse to a Read command on an invalid session.
|
||||
bool MavlinkFtpTest::_read_badsession_test(void)
|
||||
bool MavlinkFtpTest::_read_badsession_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -624,7 +624,7 @@ bool MavlinkFtpTest::_read_badsession_test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MavlinkFtpTest::_removedirectory_test(void)
|
||||
bool MavlinkFtpTest::_removedirectory_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -680,7 +680,7 @@ bool MavlinkFtpTest::_removedirectory_test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MavlinkFtpTest::_createdirectory_test(void)
|
||||
bool MavlinkFtpTest::_createdirectory_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -725,7 +725,7 @@ bool MavlinkFtpTest::_createdirectory_test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MavlinkFtpTest::_removefile_test(void)
|
||||
bool MavlinkFtpTest::_removefile_test()
|
||||
{
|
||||
MavlinkFTP::PayloadHeader payload;
|
||||
const MavlinkFTP::PayloadHeader *reply;
|
||||
|
@ -916,14 +916,14 @@ bool MavlinkFtpTest::_send_receive_msg(MavlinkFTP::PayloadHeader *payload_header
|
|||
}
|
||||
|
||||
/// @brief Cleans up an files created on microsd during testing
|
||||
void MavlinkFtpTest::_cleanup_microsd(void)
|
||||
void MavlinkFtpTest::_cleanup_microsd()
|
||||
{
|
||||
::unlink(_unittest_microsd_file);
|
||||
::rmdir(_unittest_microsd_dir);
|
||||
}
|
||||
|
||||
/// @brief Runs all the unit tests
|
||||
bool MavlinkFtpTest::run_tests(void)
|
||||
bool MavlinkFtpTest::run_tests()
|
||||
{
|
||||
ut_run_test(_ack_test);
|
||||
ut_run_test(_bad_opcode_test);
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
|
||||
extern "C" __EXPORT int mc_pos_control_tests_main(int argc, char *argv[]);
|
||||
|
||||
bool mcPosControlTests(void);
|
||||
bool mcPosControlTests();
|
||||
|
||||
//#include "../mc_pos_control_main.cpp"
|
||||
class MulticopterPositionControl
|
||||
|
@ -61,7 +61,7 @@ public:
|
|||
McPosControlTests();
|
||||
virtual ~McPosControlTests();
|
||||
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool cross_sphere_line_test();
|
||||
|
@ -75,7 +75,7 @@ McPosControlTests::~McPosControlTests()
|
|||
{
|
||||
}
|
||||
|
||||
bool McPosControlTests::cross_sphere_line_test(void)
|
||||
bool McPosControlTests::cross_sphere_line_test()
|
||||
{
|
||||
MulticopterPositionControl *control = {};
|
||||
|
||||
|
@ -182,7 +182,7 @@ bool McPosControlTests::cross_sphere_line_test(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool McPosControlTests::run_tests(void)
|
||||
bool McPosControlTests::run_tests()
|
||||
{
|
||||
ut_run_test(cross_sphere_line_test);
|
||||
|
||||
|
|
|
@ -91,7 +91,7 @@ int baro_init();
|
|||
|
||||
|
||||
int
|
||||
sensors_init(void)
|
||||
sensors_init()
|
||||
{
|
||||
int ret;
|
||||
int ret_combined = 0;
|
||||
|
|
|
@ -435,7 +435,7 @@ void uORB::Manager::set_uorb_communicator(uORBCommunicator::IChannel *channel)
|
|||
}
|
||||
}
|
||||
|
||||
uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator(void)
|
||||
uORBCommunicator::IChannel *uORB::Manager::get_uorb_communicator()
|
||||
{
|
||||
return _comm_channel;
|
||||
}
|
||||
|
|
|
@ -60,7 +60,7 @@ uORBTest::UnitTest &uORBTest::UnitTest::instance()
|
|||
return t;
|
||||
}
|
||||
|
||||
int uORBTest::UnitTest::pubsublatency_main(void)
|
||||
int uORBTest::UnitTest::pubsublatency_main()
|
||||
{
|
||||
/* poll on test topic and output latency */
|
||||
float latency_integral = 0.0f;
|
||||
|
|
|
@ -48,7 +48,7 @@ UnitTest::~UnitTest()
|
|||
{
|
||||
}
|
||||
|
||||
void UnitTest::print_results(void)
|
||||
void UnitTest::print_results()
|
||||
{
|
||||
if (_tests_failed) {
|
||||
PX4_ERR("SOME TESTS FAILED");
|
||||
|
|
|
@ -193,7 +193,7 @@ namespace
|
|||
ADCSIM *g_adc;
|
||||
|
||||
int
|
||||
test(void)
|
||||
test()
|
||||
{
|
||||
DevHandle h;
|
||||
DevMgr::getHandle(ADCSIM0_DEVICE_PATH, h);
|
||||
|
|
|
@ -133,7 +133,7 @@ private:
|
|||
/**
|
||||
* Worker task: main GPS thread that configures the GPS and parses incoming data, always running
|
||||
*/
|
||||
void task_main(void);
|
||||
void task_main();
|
||||
|
||||
/**
|
||||
* Set the baudrate of the UART to the GPS
|
||||
|
|
|
@ -56,7 +56,7 @@
|
|||
|
||||
namespace px4
|
||||
{
|
||||
void init_once(void);
|
||||
void init_once();
|
||||
}
|
||||
|
||||
using namespace std;
|
||||
|
@ -260,7 +260,7 @@ static void process_line(string &line, bool exit_on_fail)
|
|||
run_cmd(appargs, exit_on_fail);
|
||||
}
|
||||
|
||||
static void restore_term(void)
|
||||
static void restore_term()
|
||||
{
|
||||
cout << "Restoring terminal\n";
|
||||
tcsetattr(0, TCSANOW, &orig_term);
|
||||
|
|
|
@ -67,9 +67,9 @@ __END_DECLS
|
|||
namespace px4
|
||||
{
|
||||
|
||||
void init_once(void);
|
||||
void init_once();
|
||||
|
||||
void init_once(void)
|
||||
void init_once()
|
||||
{
|
||||
_shell_task_id = pthread_self();
|
||||
//printf("[init] shell id: %lu\n", (unsigned long)_shell_task_id);
|
||||
|
|
|
@ -15,20 +15,20 @@
|
|||
class AutoDeclinationTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool autodeclination_check();
|
||||
};
|
||||
|
||||
bool AutoDeclinationTest::autodeclination_check(void)
|
||||
bool AutoDeclinationTest::autodeclination_check()
|
||||
{
|
||||
ut_assert("declination differs more than 1 degree", get_mag_declination(47.0, 8.0) - 0.6f < 0.5f);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AutoDeclinationTest::run_tests(void)
|
||||
bool AutoDeclinationTest::run_tests()
|
||||
{
|
||||
ut_run_test(autodeclination_check);
|
||||
|
||||
|
|
|
@ -22,14 +22,14 @@ typedef union {
|
|||
class FloatTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool singlePrecisionTests();
|
||||
bool doublePrecisionTests();
|
||||
};
|
||||
|
||||
bool FloatTest::singlePrecisionTests(void)
|
||||
bool FloatTest::singlePrecisionTests()
|
||||
{
|
||||
float sinf_zero = sinf(0.0f);
|
||||
float sinf_one = sinf(1.0f);
|
||||
|
@ -83,7 +83,7 @@ bool FloatTest::singlePrecisionTests(void)
|
|||
}
|
||||
|
||||
|
||||
bool FloatTest::doublePrecisionTests(void)
|
||||
bool FloatTest::doublePrecisionTests()
|
||||
{
|
||||
float f1 = 1.55f;
|
||||
|
||||
|
@ -138,7 +138,7 @@ bool FloatTest::doublePrecisionTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool FloatTest::run_tests(void)
|
||||
bool FloatTest::run_tests()
|
||||
{
|
||||
ut_run_test(singlePrecisionTests);
|
||||
ut_run_test(doublePrecisionTests);
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
class HysteresisTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool _init_false();
|
||||
|
|
|
@ -20,14 +20,14 @@ typedef union {
|
|||
class IntTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool math64bitTests();
|
||||
bool math3264MixedMathTests();
|
||||
};
|
||||
|
||||
bool IntTest::math64bitTests(void)
|
||||
bool IntTest::math64bitTests()
|
||||
{
|
||||
int64_t large = 354156329598;
|
||||
int64_t calc = large * 5;
|
||||
|
@ -37,7 +37,7 @@ bool IntTest::math64bitTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool IntTest::math3264MixedMathTests(void)
|
||||
bool IntTest::math3264MixedMathTests()
|
||||
{
|
||||
int32_t small = 50;
|
||||
int32_t large_int = 2147483647; // MAX INT value
|
||||
|
@ -50,7 +50,7 @@ bool IntTest::math3264MixedMathTests(void)
|
|||
}
|
||||
|
||||
|
||||
bool IntTest::run_tests(void)
|
||||
bool IntTest::run_tests()
|
||||
{
|
||||
ut_run_test(math64bitTests);
|
||||
ut_run_test(math3264MixedMathTests);
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
class MathlibTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool testVector2();
|
||||
|
@ -79,7 +79,7 @@ private:
|
|||
|
||||
using namespace math;
|
||||
|
||||
bool MathlibTest::testVector2(void)
|
||||
bool MathlibTest::testVector2()
|
||||
{
|
||||
{
|
||||
Vector<2> v;
|
||||
|
@ -101,7 +101,7 @@ bool MathlibTest::testVector2(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testVector3(void)
|
||||
bool MathlibTest::testVector3()
|
||||
{
|
||||
|
||||
{
|
||||
|
@ -139,7 +139,7 @@ bool MathlibTest::testVector3(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testVector4(void)
|
||||
bool MathlibTest::testVector4()
|
||||
{
|
||||
{
|
||||
Vector<4> v;
|
||||
|
@ -160,7 +160,7 @@ bool MathlibTest::testVector4(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testVector10(void)
|
||||
bool MathlibTest::testVector10()
|
||||
{
|
||||
{
|
||||
Vector<10> v1;
|
||||
|
@ -173,7 +173,7 @@ bool MathlibTest::testVector10(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testMatrix3x3(void)
|
||||
bool MathlibTest::testMatrix3x3()
|
||||
{
|
||||
{
|
||||
Matrix<3, 3> m1;
|
||||
|
@ -188,7 +188,7 @@ bool MathlibTest::testMatrix3x3(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testMatrix10x10(void)
|
||||
bool MathlibTest::testMatrix10x10()
|
||||
{
|
||||
{
|
||||
Matrix<10, 10> m1;
|
||||
|
@ -204,7 +204,7 @@ bool MathlibTest::testMatrix10x10(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testMatrixNonsymmetric(void)
|
||||
bool MathlibTest::testMatrixNonsymmetric()
|
||||
{
|
||||
int rc = true;
|
||||
{
|
||||
|
@ -268,7 +268,7 @@ bool MathlibTest::testMatrixNonsymmetric(void)
|
|||
return rc;
|
||||
}
|
||||
|
||||
bool MathlibTest::testRotationMatrixQuaternion(void)
|
||||
bool MathlibTest::testRotationMatrixQuaternion()
|
||||
{
|
||||
// test conversion rotation matrix to quaternion and back
|
||||
math::Matrix<3, 3> R_orig;
|
||||
|
@ -299,7 +299,7 @@ bool MathlibTest::testRotationMatrixQuaternion(void)
|
|||
}
|
||||
|
||||
|
||||
bool MathlibTest::testQuaternionfrom_dcm(void)
|
||||
bool MathlibTest::testQuaternionfrom_dcm()
|
||||
{
|
||||
// test against some known values
|
||||
float tol = 0.0001f;
|
||||
|
@ -318,7 +318,7 @@ bool MathlibTest::testQuaternionfrom_dcm(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testQuaternionfrom_euler(void)
|
||||
bool MathlibTest::testQuaternionfrom_euler()
|
||||
{
|
||||
float tol = 0.0001f;
|
||||
math::Quaternion q_true = {1.0f, 0.0f, 0.0f, 0.0f};
|
||||
|
@ -353,7 +353,7 @@ bool MathlibTest::testQuaternionfrom_euler(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::testQuaternionRotate(void)
|
||||
bool MathlibTest::testQuaternionRotate()
|
||||
{
|
||||
// test quaternion method "rotate" (rotate vector by quaternion)
|
||||
Vector<3> vector = {1.0f, 1.0f, 1.0f};
|
||||
|
@ -419,7 +419,7 @@ bool MathlibTest::testQuaternionRotate(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MathlibTest::run_tests(void)
|
||||
bool MathlibTest::run_tests()
|
||||
{
|
||||
ut_run_test(testVector2);
|
||||
ut_run_test(testVector3);
|
||||
|
|
|
@ -10,7 +10,7 @@ using namespace matrix;
|
|||
class MatrixTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
|
||||
private:
|
||||
bool attitudeTests();
|
||||
|
@ -32,7 +32,7 @@ private:
|
|||
bool dcmRenormTests();
|
||||
};
|
||||
|
||||
bool MatrixTest::run_tests(void)
|
||||
bool MatrixTest::run_tests()
|
||||
{
|
||||
ut_run_test(attitudeTests);
|
||||
ut_run_test(filterTests);
|
||||
|
@ -63,7 +63,7 @@ template class matrix::Quaternion<float>;
|
|||
template class matrix::Euler<float>;
|
||||
template class matrix::Dcm<float>;
|
||||
|
||||
bool MatrixTest::attitudeTests(void)
|
||||
bool MatrixTest::attitudeTests()
|
||||
{
|
||||
double eps = 1e-6;
|
||||
|
||||
|
@ -292,7 +292,7 @@ bool MatrixTest::attitudeTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::filterTests(void)
|
||||
bool MatrixTest::filterTests()
|
||||
{
|
||||
const size_t n_x = 6;
|
||||
const size_t n_y = 5;
|
||||
|
@ -315,7 +315,7 @@ bool MatrixTest::filterTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::helperTests(void)
|
||||
bool MatrixTest::helperTests()
|
||||
{
|
||||
ut_test(fabs(wrap_pi(4.0) - (4.0 - 2 * M_PI)) < 1e-5);
|
||||
ut_test(fabs(wrap_pi(-4.0) - (-4.0 + 2 * M_PI)) < 1e-5);
|
||||
|
@ -338,7 +338,7 @@ Vector<float, 6> f(float t, const Matrix<float, 6, 1> &y, const Matrix<float, 3,
|
|||
return v * ones<float, 6, 1>();
|
||||
}
|
||||
|
||||
bool MatrixTest::integrationTests(void)
|
||||
bool MatrixTest::integrationTests()
|
||||
{
|
||||
Vector<float, 6> y = ones<float, 6, 1>();
|
||||
Vector<float, 3> u = ones<float, 3, 1>();
|
||||
|
@ -354,7 +354,7 @@ bool MatrixTest::integrationTests(void)
|
|||
|
||||
template class matrix::SquareMatrix<float, 3>;
|
||||
|
||||
bool MatrixTest::inverseTests(void)
|
||||
bool MatrixTest::inverseTests()
|
||||
{
|
||||
float data[9] = {0, 2, 3,
|
||||
4, 5, 6,
|
||||
|
@ -380,7 +380,7 @@ bool MatrixTest::inverseTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::matrixAssignmentTests(void)
|
||||
bool MatrixTest::matrixAssignmentTests()
|
||||
{
|
||||
Matrix3f m;
|
||||
m.setZero();
|
||||
|
@ -461,7 +461,7 @@ bool MatrixTest::matrixAssignmentTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::matrixMultTests(void)
|
||||
bool MatrixTest::matrixMultTests()
|
||||
{
|
||||
float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1};
|
||||
Matrix3f A(data);
|
||||
|
@ -485,7 +485,7 @@ bool MatrixTest::matrixMultTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::matrixScalarMultTests(void)
|
||||
bool MatrixTest::matrixScalarMultTests()
|
||||
{
|
||||
float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9};
|
||||
Matrix3f A(data);
|
||||
|
@ -500,7 +500,7 @@ bool MatrixTest::matrixScalarMultTests(void)
|
|||
|
||||
template class matrix::Matrix<float, 3, 3>;
|
||||
|
||||
bool MatrixTest::setIdentityTests(void)
|
||||
bool MatrixTest::setIdentityTests()
|
||||
{
|
||||
Matrix3f A;
|
||||
A.setIdentity();
|
||||
|
@ -519,7 +519,7 @@ bool MatrixTest::setIdentityTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::sliceTests(void)
|
||||
bool MatrixTest::sliceTests()
|
||||
{
|
||||
float data[9] = {0, 2, 3,
|
||||
4, 5, 6,
|
||||
|
@ -554,7 +554,7 @@ bool MatrixTest::sliceTests(void)
|
|||
}
|
||||
|
||||
|
||||
bool MatrixTest::squareMatrixTests(void)
|
||||
bool MatrixTest::squareMatrixTests()
|
||||
{
|
||||
float data[9] = {1, 2, 3,
|
||||
4, 5, 6,
|
||||
|
@ -581,7 +581,7 @@ bool MatrixTest::squareMatrixTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::transposeTests(void)
|
||||
bool MatrixTest::transposeTests()
|
||||
{
|
||||
float data[6] = {1, 2, 3, 4, 5, 6};
|
||||
Matrix<float, 2, 3> A(data);
|
||||
|
@ -593,7 +593,7 @@ bool MatrixTest::transposeTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::vectorTests(void)
|
||||
bool MatrixTest::vectorTests()
|
||||
{
|
||||
float data1[] = {1, 2, 3, 4, 5};
|
||||
float data2[] = {6, 7, 8, 9, 10};
|
||||
|
@ -611,7 +611,7 @@ bool MatrixTest::vectorTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::vector2Tests(void)
|
||||
bool MatrixTest::vector2Tests()
|
||||
{
|
||||
Vector2f a(1, 0);
|
||||
Vector2f b(0, 1);
|
||||
|
@ -636,7 +636,7 @@ bool MatrixTest::vector2Tests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::vector3Tests(void)
|
||||
bool MatrixTest::vector3Tests()
|
||||
{
|
||||
Vector3f a(1, 0, 0);
|
||||
Vector3f b(0, 1, 0);
|
||||
|
@ -653,7 +653,7 @@ bool MatrixTest::vector3Tests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::vectorAssignmentTests(void)
|
||||
bool MatrixTest::vectorAssignmentTests()
|
||||
{
|
||||
Vector3f v;
|
||||
v(0) = 1;
|
||||
|
@ -680,7 +680,7 @@ bool MatrixTest::vectorAssignmentTests(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool MatrixTest::dcmRenormTests(void)
|
||||
bool MatrixTest::dcmRenormTests()
|
||||
{
|
||||
bool verbose = true;
|
||||
|
||||
|
|
|
@ -105,7 +105,7 @@ static bool should_prearm = false;
|
|||
class MixerTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
virtual bool run_tests(void);
|
||||
virtual bool run_tests();
|
||||
MixerTest();
|
||||
|
||||
private:
|
||||
|
@ -128,7 +128,7 @@ MixerTest::MixerTest() : UnitTest(),
|
|||
{
|
||||
}
|
||||
|
||||
bool MixerTest::run_tests(void)
|
||||
bool MixerTest::run_tests()
|
||||
{
|
||||
ut_run_test(loadIOPass);
|
||||
ut_run_test(loadQuadTest);
|
||||
|
|
Loading…
Reference in New Issue