px4-firmware/test/mavsdk_tests/autopilot_tester.h

288 lines
11 KiB
C
Raw Permalink Normal View History

2020-03-17 12:15:34 -03:00
/****************************************************************************
*
2021-11-26 11:52:14 -04:00
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
2020-03-17 12:15:34 -03:00
*
* 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.
*
****************************************************************************/
2019-10-02 15:14:18 -03:00
#pragma once
#include <mavsdk/mavsdk.h>
#include <mavsdk/geometry.h>
#include <mavsdk/plugins/action/action.h>
#include <mavsdk/plugins/failure/failure.h>
#include <mavsdk/plugins/info/info.h>
2020-07-31 04:45:12 -03:00
#include <mavsdk/plugins/manual_control/manual_control.h>
2019-10-02 15:14:18 -03:00
#include <mavsdk/plugins/mission/mission.h>
#include <mavsdk/plugins/mission_raw/mission_raw.h>
#include <mavsdk/plugins/offboard/offboard.h>
2019-10-02 15:14:18 -03:00
#include <mavsdk/plugins/telemetry/telemetry.h>
#include <mavsdk/plugins/param/param.h>
2019-10-02 15:14:18 -03:00
#include "catch2/catch.hpp"
#include <atomic>
2019-10-02 15:14:18 -03:00
#include <chrono>
#include <ctime>
2020-07-31 04:45:12 -03:00
#include <iostream>
2019-10-02 15:14:18 -03:00
#include <memory>
#include <optional>
2019-10-02 15:14:18 -03:00
#include <thread>
extern std::string connection_url;
extern std::optional<float> speed_factor;
using namespace mavsdk;
using namespace mavsdk::geometry;
inline std::string time_str()
{
time_t rawtime;
time(&rawtime);
struct tm *timeinfo = localtime(&rawtime);
char time_buffer[18];
strftime(time_buffer, 18, "[%I:%M:%S|Info ] ", timeinfo);
return time_buffer;
}
2020-03-17 12:15:34 -03:00
class AutopilotTester
{
2019-10-02 15:14:18 -03:00
public:
2020-03-17 12:15:34 -03:00
struct MissionOptions {
double leg_length_m {20.0};
double relative_altitude_m {10.0};
bool rtl_at_end {false};
2020-07-09 12:36:24 -03:00
bool fly_through {false};
2020-03-17 12:15:34 -03:00
};
enum class HeightSource {
Baro,
Gps
};
enum class RcLossException {
Mission = 0,
Hold = 1,
Offboard = 2
};
AutopilotTester();
~AutopilotTester();
2020-03-17 12:15:34 -03:00
void connect(const std::string uri);
/**
* @brief Wait until vehicle's system status is healthy & is able to arm
*/
2020-03-17 12:15:34 -03:00
void wait_until_ready();
2020-03-17 12:15:34 -03:00
void store_home();
void check_home_within(float acceptance_radius_m);
2020-07-31 04:45:12 -03:00
void check_home_not_within(float min_distance_m);
2020-03-17 12:15:34 -03:00
void set_takeoff_altitude(const float altitude_m);
2021-11-26 11:52:14 -04:00
void set_rtl_altitude(const float altitude_m);
void set_height_source(HeightSource height_source);
void set_rc_loss_exception(RcLossException mask);
2020-03-17 12:15:34 -03:00
void arm();
void takeoff();
void land();
void transition_to_fixedwing();
void transition_to_multicopter();
void wait_until_disarmed(std::chrono::seconds timeout_duration = std::chrono::seconds(60));
2021-11-26 11:52:14 -04:00
void wait_until_hovering(); // TODO: name suggests, that function waits for drone velocity to be zero and not just drone in the air
void wait_until_altitude(float rel_altitude_m, std::chrono::seconds timeout);
void wait_until_speed_lower_than(float speed, std::chrono::seconds timeout);
2020-03-17 12:15:34 -03:00
void prepare_square_mission(MissionOptions mission_options);
2020-07-09 12:36:24 -03:00
void prepare_straight_mission(MissionOptions mission_options);
2020-03-17 12:15:34 -03:00
void execute_mission();
void execute_mission_and_lose_gps();
void execute_mission_and_lose_mag();
2020-06-26 11:43:51 -03:00
void execute_mission_and_get_mag_stuck();
void execute_mission_and_lose_baro();
2020-06-26 09:48:53 -03:00
void execute_mission_and_get_baro_stuck();
void load_qgc_mission_raw_and_move_here(const std::string &plan_file);
void execute_mission_raw();
2020-03-17 12:15:34 -03:00
void execute_rtl();
2021-11-26 11:52:14 -04:00
void execute_land();
void offboard_goto(const Offboard::PositionNedYaw &target, float acceptance_radius_m = 0.3f,
2020-03-17 12:15:34 -03:00
std::chrono::seconds timeout_duration = std::chrono::seconds(60));
void offboard_land();
2020-07-31 04:45:12 -03:00
void fly_forward_in_posctl();
void fly_forward_in_altctl();
void fly_forward_in_offboard_attitude();
2020-03-17 12:15:34 -03:00
void request_ground_truth();
void check_mission_item_speed_above(int item_index, float min_speed_m_s);
void check_tracks_mission(float corridor_radius_m = 1.5f);
void check_tracks_mission_raw(float corridor_radius_m = 1.f, bool reverse = false);
2021-11-26 11:52:14 -04:00
void start_checking_altitude(const float max_deviation_m);
void stop_checking_altitude();
New follow-me flight task rename follow_me_status to follow_target_status enable follow_target_estimator on skynode implement the responsiveness parameter: The responsiveness parameter should behave similarly to the previous follow-me implementation in navigator. The difference here is that there are now two separate gains for position and velocity fusion. The previous implemenation in navigator had no velocity fusion. Allow follow-me to be flown without RC SITL tests for follow-me flight task This includes: - Testing the setting for the follow-me angle - Testing that streaming position only or position and velocity measurements both work - Testing that RC override works Most of these tests are done with a simulated model of a point object that moves on a straight line. So nothing too spectacular. But it makes the test checks much easier. Since the estimator for the target actually checks new measurements and compares them to old ones, I also added random gausian noise to the measurements with a fixed seed for deterministic randomness. So repeated runs produce exactly the same results over and over. Half of the angles are still missing in MAVSDK. Need to create an upstream PR to add center left/right and rear left/right options. These and the corresponding SITL tests need to be implemented later. sitl: Increase position tolerance during follow-me Astro seems to barely exceed the current tolerance (4.3 !< 4.0) causing CI to fail. The point of the CI test is not to check the accuracy of the flight behaviour, but only the fact that the drone is doing the expected thing. So the exact value of this tolerance is not really important. follow-me: gimbal control in follow-me follow-me: create sub-routines in flight task class follow-me: use ground-dist for emergency ascent dist_bottom is only defined when a ground facing distance sensor exist. It's therefore better to use dist_ground instead, which has the distance to the home altitude if no distance sensor is available. As a consequence it will only be possible to use follow-me in a valley when the drone has a distance sensor. follow-me: point gimbal to the ground in 2D mode follow-me: another fuzzy msg handling for the estimator follow-me: bugfix in acceleration saturation limit follow-me: parameter for filter delay compensation mantis: dont use flow for terrain estimation follow-me: default responsiveness 0.5 -> 0.1 0.5 is way too jerky in real and simulated tests. flight_task: clarify comments for bottom distance follow-me: minor comment improvement follow-me: [debug] log emergency_ascent follow-me: [debug] log gimbal pitch follow-me: [debug] status values for follow-me estimator follow-me: setting for gimbal tracking mode follow-me: release gimbal control at destruction mavsdk: cosmetics :lipstick:
2021-07-20 04:11:17 -03:00
void check_current_altitude(float target_rel_altitude_m, float max_distance_m = 1.5f);
void execute_rtl_when_reaching_mission_sequence(int sequence_number);
2021-11-26 11:52:14 -04:00
// Blocking call to get the drone's current position in NED frame
std::array<float, 3> get_current_position_ned();
void set_param_int(const std::string &param, int32_t value)
{
CHECK(_param->set_param_int(param, value) == Param::Result::Success);
}
2021-11-26 11:52:14 -04:00
protected:
mavsdk::Param *getParams() const { return _param.get();}
mavsdk::Telemetry *getTelemetry() const { return _telemetry.get();}
New follow-me flight task rename follow_me_status to follow_target_status enable follow_target_estimator on skynode implement the responsiveness parameter: The responsiveness parameter should behave similarly to the previous follow-me implementation in navigator. The difference here is that there are now two separate gains for position and velocity fusion. The previous implemenation in navigator had no velocity fusion. Allow follow-me to be flown without RC SITL tests for follow-me flight task This includes: - Testing the setting for the follow-me angle - Testing that streaming position only or position and velocity measurements both work - Testing that RC override works Most of these tests are done with a simulated model of a point object that moves on a straight line. So nothing too spectacular. But it makes the test checks much easier. Since the estimator for the target actually checks new measurements and compares them to old ones, I also added random gausian noise to the measurements with a fixed seed for deterministic randomness. So repeated runs produce exactly the same results over and over. Half of the angles are still missing in MAVSDK. Need to create an upstream PR to add center left/right and rear left/right options. These and the corresponding SITL tests need to be implemented later. sitl: Increase position tolerance during follow-me Astro seems to barely exceed the current tolerance (4.3 !< 4.0) causing CI to fail. The point of the CI test is not to check the accuracy of the flight behaviour, but only the fact that the drone is doing the expected thing. So the exact value of this tolerance is not really important. follow-me: gimbal control in follow-me follow-me: create sub-routines in flight task class follow-me: use ground-dist for emergency ascent dist_bottom is only defined when a ground facing distance sensor exist. It's therefore better to use dist_ground instead, which has the distance to the home altitude if no distance sensor is available. As a consequence it will only be possible to use follow-me in a valley when the drone has a distance sensor. follow-me: point gimbal to the ground in 2D mode follow-me: another fuzzy msg handling for the estimator follow-me: bugfix in acceleration saturation limit follow-me: parameter for filter delay compensation mantis: dont use flow for terrain estimation follow-me: default responsiveness 0.5 -> 0.1 0.5 is way too jerky in real and simulated tests. flight_task: clarify comments for bottom distance follow-me: minor comment improvement follow-me: [debug] log emergency_ascent follow-me: [debug] log gimbal pitch follow-me: [debug] status values for follow-me estimator follow-me: setting for gimbal tracking mode follow-me: release gimbal control at destruction mavsdk: cosmetics :lipstick:
2021-07-20 04:11:17 -03:00
mavsdk::ManualControl *getManualControl() const { return _manual_control.get();}
2021-11-26 11:52:14 -04:00
std::shared_ptr<System> get_system() { return _mavsdk.systems().at(0);}
New follow-me flight task rename follow_me_status to follow_target_status enable follow_target_estimator on skynode implement the responsiveness parameter: The responsiveness parameter should behave similarly to the previous follow-me implementation in navigator. The difference here is that there are now two separate gains for position and velocity fusion. The previous implemenation in navigator had no velocity fusion. Allow follow-me to be flown without RC SITL tests for follow-me flight task This includes: - Testing the setting for the follow-me angle - Testing that streaming position only or position and velocity measurements both work - Testing that RC override works Most of these tests are done with a simulated model of a point object that moves on a straight line. So nothing too spectacular. But it makes the test checks much easier. Since the estimator for the target actually checks new measurements and compares them to old ones, I also added random gausian noise to the measurements with a fixed seed for deterministic randomness. So repeated runs produce exactly the same results over and over. Half of the angles are still missing in MAVSDK. Need to create an upstream PR to add center left/right and rear left/right options. These and the corresponding SITL tests need to be implemented later. sitl: Increase position tolerance during follow-me Astro seems to barely exceed the current tolerance (4.3 !< 4.0) causing CI to fail. The point of the CI test is not to check the accuracy of the flight behaviour, but only the fact that the drone is doing the expected thing. So the exact value of this tolerance is not really important. follow-me: gimbal control in follow-me follow-me: create sub-routines in flight task class follow-me: use ground-dist for emergency ascent dist_bottom is only defined when a ground facing distance sensor exist. It's therefore better to use dist_ground instead, which has the distance to the home altitude if no distance sensor is available. As a consequence it will only be possible to use follow-me in a valley when the drone has a distance sensor. follow-me: point gimbal to the ground in 2D mode follow-me: another fuzzy msg handling for the estimator follow-me: bugfix in acceleration saturation limit follow-me: parameter for filter delay compensation mantis: dont use flow for terrain estimation follow-me: default responsiveness 0.5 -> 0.1 0.5 is way too jerky in real and simulated tests. flight_task: clarify comments for bottom distance follow-me: minor comment improvement follow-me: [debug] log emergency_ascent follow-me: [debug] log gimbal pitch follow-me: [debug] status values for follow-me estimator follow-me: setting for gimbal tracking mode follow-me: release gimbal control at destruction mavsdk: cosmetics :lipstick:
2021-07-20 04:11:17 -03:00
Telemetry::GroundTruth getHome()
{
// Check if home was stored before it is accessed
CHECK(_home.absolute_altitude_m != NAN);
CHECK(_home.latitude_deg != NAN);
CHECK(_home.longitude_deg != NAN);
return _home;
}
template<typename Rep, typename Period>
void sleep_for(std::chrono::duration<Rep, Period> duration)
{
const std::chrono::microseconds duration_us(duration);
if (_telemetry && _telemetry->attitude_quaternion().timestamp_us != 0) {
const int64_t start_time_us = _telemetry->attitude_quaternion().timestamp_us;
while (true) {
// Hopefully this is often enough not to have PX4 time out on us.
std::this_thread::sleep_for(std::chrono::milliseconds(1));
const int64_t elapsed_time_us = _telemetry->attitude_quaternion().timestamp_us - start_time_us;
if (elapsed_time_us > duration_us.count()) {
return;
}
}
} else {
std::this_thread::sleep_for(duration);
}
}
2019-10-02 15:14:18 -03:00
private:
2020-03-17 12:15:34 -03:00
mavsdk::geometry::CoordinateTransformation get_coordinate_transformation();
mavsdk::Mission::MissionItem create_mission_item(
2020-03-17 12:15:34 -03:00
const mavsdk::geometry::CoordinateTransformation::LocalCoordinate &local_coordinate,
const MissionOptions &mission_options,
const mavsdk::geometry::CoordinateTransformation &ct);
bool ground_truth_horizontal_position_close_to(const Telemetry::GroundTruth &target_pos, float acceptance_radius_m);
2020-07-31 04:45:12 -03:00
bool ground_truth_horizontal_position_far_from(const Telemetry::GroundTruth &target_pos, float min_distance_m);
bool estimated_position_close_to(const Offboard::PositionNedYaw &target_pos, float acceptance_radius_m);
bool estimated_horizontal_position_close_to(const Offboard::PositionNedYaw &target_pos, float acceptance_radius_m);
void start_and_wait_for_mission_sequence(int sequence_number);
void start_and_wait_for_mission_sequence_raw(int sequence_number);
void wait_for_flight_mode(Telemetry::FlightMode flight_mode, std::chrono::seconds timeout);
void wait_for_landed_state(Telemetry::LandedState landed_state, std::chrono::seconds timeout);
void wait_for_mission_finished(std::chrono::seconds timeout);
void wait_for_mission_raw_finished(std::chrono::seconds timeout);
void move_mission_raw_here(std::vector<mavsdk::MissionRaw::MissionItem> &mission_items);
2020-03-17 12:15:34 -03:00
void report_speed_factor();
/**
* @brief Continue polling until condition returns true or we have a timeout
*
* @param fun Boolean returning function. When true, the polling terminates.
* @param duration Timeout for polling in `std::chrono::` time unit
*/
template<typename Rep, typename Period>
bool poll_condition_with_timeout(
std::function<bool()> fun, std::chrono::duration<Rep, Period> duration)
{
static constexpr unsigned check_resolution = 100;
const std::chrono::microseconds duration_us(duration);
if (_telemetry && _telemetry->attitude_quaternion().timestamp_us != 0) {
// A system is connected. We can base the timeouts on the autopilot time.
const int64_t start_time_us = _telemetry->attitude_quaternion().timestamp_us;
while (!fun()) {
std::this_thread::sleep_for(duration_us / check_resolution);
// This might potentially loop forever and the test needs to be killed by a watchdog outside.
// The reason not to include an absolute timeout here is that it can happen if the host is
// busy and PX4 doesn't run fast enough.
const int64_t elapsed_time_us = _telemetry->attitude_quaternion().timestamp_us - start_time_us;
if (elapsed_time_us > duration_us.count()) {
std::cout << time_str() << "Timeout, connected to vehicle but waiting for test for " << static_cast<double>
(elapsed_time_us) / 1e6 << " seconds\n";
return false;
}
}
} else {
// Nothing is connected yet. Use the host time.
const auto start_time = std::chrono::steady_clock::now();
while (!fun()) {
std::this_thread::sleep_for(duration_us / check_resolution);
const auto elapsed_time_us = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() -
start_time);
if (elapsed_time_us > duration_us) {
std::cout << time_str() << "Timeout, waiting for the vehicle for "
<< elapsed_time_us.count() * std::chrono::steady_clock::period::num
/ static_cast<double>(std::chrono::steady_clock::period::den)
<< " seconds\n";
return false;
}
}
}
return true;
}
2020-03-17 12:15:34 -03:00
mavsdk::Mavsdk _mavsdk{};
std::unique_ptr<mavsdk::Action> _action{};
std::unique_ptr<mavsdk::Failure> _failure{};
std::unique_ptr<mavsdk::Info> _info{};
2020-07-31 04:45:12 -03:00
std::unique_ptr<mavsdk::ManualControl> _manual_control{};
2020-03-17 12:15:34 -03:00
std::unique_ptr<mavsdk::Mission> _mission{};
std::unique_ptr<mavsdk::MissionRaw> _mission_raw{};
2020-03-17 12:15:34 -03:00
std::unique_ptr<mavsdk::Offboard> _offboard{};
std::unique_ptr<mavsdk::Param> _param{};
std::unique_ptr<mavsdk::Telemetry> _telemetry{};
2020-03-17 12:15:34 -03:00
Telemetry::GroundTruth _home{NAN, NAN, NAN};
std::atomic<bool> _should_exit {false};
std::thread _real_time_report_thread {};
2019-10-02 15:14:18 -03:00
};