mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavsdk_tests: report speed factor every second
This helps in debugging slow CI.
This commit is contained in:
parent
e05a4badf8
commit
1e88939605
@ -35,8 +35,24 @@
|
||||
#include "math_helpers.h"
|
||||
#include <iostream>
|
||||
#include <future>
|
||||
#include <thread>
|
||||
|
||||
std::string connection_url {"udp://"};
|
||||
std::optional<float> speed_factor {std::nullopt};
|
||||
|
||||
AutopilotTester::AutopilotTester() :
|
||||
_real_time_report_thread([this]()
|
||||
{
|
||||
report_speed_factor();
|
||||
})
|
||||
{
|
||||
}
|
||||
|
||||
AutopilotTester::~AutopilotTester()
|
||||
{
|
||||
_should_exit = true;
|
||||
_real_time_report_thread.join();
|
||||
}
|
||||
|
||||
void AutopilotTester::connect(const std::string uri)
|
||||
{
|
||||
@ -603,3 +619,25 @@ void AutopilotTester::wait_for_mission_finished(std::chrono::seconds timeout)
|
||||
|
||||
REQUIRE(fut.wait_for(timeout) == std::future_status::ready);
|
||||
}
|
||||
|
||||
void AutopilotTester::report_speed_factor()
|
||||
{
|
||||
// We check the exit flag more often than the speed factor.
|
||||
unsigned counter = 0;
|
||||
|
||||
while (!_should_exit) {
|
||||
if (counter++ % 10 == 0) {
|
||||
if (_info != nullptr) {
|
||||
std::cout << "Current speed factor: " << _info->get_speed_factor().second ;
|
||||
|
||||
if (speed_factor.has_value()) {
|
||||
std::cout << " (set: " << speed_factor.value() << ')';
|
||||
}
|
||||
|
||||
std::cout << '\n';
|
||||
}
|
||||
}
|
||||
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
}
|
||||
}
|
||||
|
||||
@ -44,13 +44,16 @@
|
||||
#include <mavsdk/plugins/telemetry/telemetry.h>
|
||||
#include <mavsdk/plugins/param/param.h>
|
||||
#include "catch2/catch.hpp"
|
||||
#include <atomic>
|
||||
#include <chrono>
|
||||
#include <ctime>
|
||||
#include <iostream>
|
||||
#include <memory>
|
||||
#include <optional>
|
||||
#include <thread>
|
||||
|
||||
extern std::string connection_url;
|
||||
extern std::optional<float> speed_factor;
|
||||
|
||||
using namespace mavsdk;
|
||||
using namespace mavsdk::geometry;
|
||||
@ -81,6 +84,9 @@ public:
|
||||
Gps
|
||||
};
|
||||
|
||||
AutopilotTester();
|
||||
~AutopilotTester();
|
||||
|
||||
void connect(const std::string uri);
|
||||
void wait_until_ready();
|
||||
void wait_until_ready_local_position_only();
|
||||
@ -131,6 +137,8 @@ private:
|
||||
void wait_for_landed_state(Telemetry::LandedState landed_state, std::chrono::seconds timeout);
|
||||
void wait_for_mission_finished(std::chrono::seconds timeout);
|
||||
|
||||
void report_speed_factor();
|
||||
|
||||
template<typename Rep, typename Period>
|
||||
bool poll_condition_with_timeout(
|
||||
std::function<bool()> fun, std::chrono::duration<Rep, Period> duration)
|
||||
@ -216,4 +224,7 @@ private:
|
||||
std::unique_ptr<mavsdk::Telemetry> _telemetry{};
|
||||
|
||||
Telemetry::GroundTruth _home{NAN, NAN, NAN};
|
||||
|
||||
std::atomic<bool> _should_exit {false};
|
||||
std::thread _real_time_report_thread {};
|
||||
};
|
||||
|
||||
@ -436,6 +436,7 @@ class Tester:
|
||||
test['model'],
|
||||
case,
|
||||
self.config['mavlink_connection'],
|
||||
self.speed_factor,
|
||||
self.verbose)
|
||||
self.active_runners.append(mavsdk_tests_runner)
|
||||
|
||||
|
||||
@ -279,10 +279,13 @@ class TestRunner(Runner):
|
||||
model: str,
|
||||
case: str,
|
||||
mavlink_connection: str,
|
||||
speed_factor: float,
|
||||
verbose: bool):
|
||||
super().__init__(log_dir, model, case, verbose)
|
||||
self.name = "mavsdk_tests"
|
||||
self.cwd = workspace_dir
|
||||
self.cmd = workspace_dir + \
|
||||
"/build/px4_sitl_default/mavsdk_tests/mavsdk_tests"
|
||||
self.args = ["--url", mavlink_connection, case]
|
||||
self.args = ["--url", mavlink_connection,
|
||||
"--speed-factor", str(speed_factor),
|
||||
case]
|
||||
|
||||
@ -50,6 +50,7 @@ int main(int argc, char **argv)
|
||||
|
||||
if (argv_string == "-h") {
|
||||
usage(argv[0]);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (argv_string == "--url") {
|
||||
@ -57,12 +58,40 @@ int main(int argc, char **argv)
|
||||
connection_url = argv[i + 1];
|
||||
remove_argv(argc, argv, i);
|
||||
remove_argv(argc, argv, i);
|
||||
--i;
|
||||
|
||||
} else {
|
||||
std::cerr << "No connection URL supplied" << std::endl;
|
||||
usage(argv[0]);
|
||||
return -1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (argv_string == "--speed-factor") {
|
||||
if (argc > i + 1) {
|
||||
try {
|
||||
speed_factor = std::make_optional(std::stof(argv[i + 1]));
|
||||
|
||||
} catch (const std::invalid_argument &) {
|
||||
std::cerr << "Speed factor could not be parsed" << std::endl;
|
||||
return -1;
|
||||
|
||||
} catch (const std::out_of_range &) {
|
||||
std::cerr << "Speed factor is out of range" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
remove_argv(argc, argv, i);
|
||||
remove_argv(argc, argv, i);
|
||||
--i;
|
||||
|
||||
|
||||
} else {
|
||||
std::cerr << "No speed factor supplied" << std::endl;
|
||||
usage(argv[0]);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -79,13 +108,16 @@ int main(int argc, char **argv)
|
||||
void usage(const std::string &bin_name)
|
||||
{
|
||||
std::cout << std::endl
|
||||
<< "Usage : " << bin_name << " [--url CONNECTION_URL] [catch2 arguments]" << std::endl
|
||||
<< "Connection URL format should be :" << std::endl
|
||||
<< " For TCP : tcp://[server_host][:server_port]" << std::endl
|
||||
<< " For UDP : udp://[bind_host][:bind_port]" << std::endl
|
||||
<< " For Serial : serial:///path/to/serial/dev[:baudrate]" << std::endl
|
||||
<< "For example, to connect to the simulator use URL: udp://:14540" << std::endl
|
||||
<< std::endl;
|
||||
<< "Usage : " << bin_name << " [--url CONNECTION_URL] [--speed-factor SPEED_FACTOR] [catch2 arguments]\n"
|
||||
<< "\n"
|
||||
<< " --url Connection URL format should be :\n"
|
||||
<< " For TCP : tcp://[server_host][:server_port]\n"
|
||||
<< " For UDP : udp://[bind_host][:bind_port]\n"
|
||||
<< " For Serial : serial:///path/to/serial/dev[:baudrate]\n"
|
||||
<< " For example, to connect to the simulator use URL: udp://:14540\n"
|
||||
<< "\n"
|
||||
<< " --speed-factor Speed factor to compare against, for information only\n"
|
||||
<< std::flush;
|
||||
}
|
||||
|
||||
void remove_argv(int &argc, char **argv, int pos)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user