-
-
Notifications
You must be signed in to change notification settings - Fork 521
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Implement transition to fw as an action. #150
Changes from all commits
bb7165c
4a9ef89
91e224a
28c94b5
1391e94
358234c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
cmake_minimum_required(VERSION 2.8.12) | ||
|
||
project(transition_vtol_fixed_wing) | ||
|
||
if(NOT MSVC) | ||
add_definitions("-std=c++11 -Wall -Wextra -Werror") | ||
else() | ||
add_definitions("-std=c++11 -WX -W2") | ||
set(platform_libs "Ws2_32.lib") | ||
endif() | ||
|
||
# Add DEBUG define for Debug target | ||
set(CMAKE_CXX_FLAGS_DEBUG "-DDEBUG") | ||
|
||
# This finds thread libs on Linux, Mac, and Windows. | ||
find_package(Threads REQUIRED) | ||
|
||
# Not needed if DroneCore installed system-wide | ||
include_directories( | ||
${CMAKE_SOURCE_DIR}/../../install/include | ||
) | ||
|
||
add_executable(transition_vtol_fixed_wing | ||
transition_vtol_fixed_wing.cpp | ||
) | ||
|
||
# Not needed if DroneCore installed system-wide | ||
if(MSVC) | ||
set(dronecore_lib "${CMAKE_SOURCE_DIR}/../../install/lib/dronecore.lib") | ||
else() | ||
set(dronecore_lib "${CMAKE_SOURCE_DIR}/../../install/lib/libdronecore.so") | ||
endif() | ||
|
||
target_link_libraries(transition_vtol_fixed_wing | ||
${dronecore_lib} # Remove/comment out this line if DroneCore used locally | ||
# dronecore # Uncomment/add this line if DroneCore installed system-wide | ||
${CMAKE_THREAD_LIBS_INIT} | ||
${platform_libs} | ||
) |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,143 @@ | ||
|
||
#include <dronecore/dronecore.h> | ||
#include <iostream> | ||
#include <thread> | ||
#include <chrono> | ||
#include <cstdint> | ||
|
||
using std::this_thread::sleep_for; | ||
using std::chrono::milliseconds; | ||
using namespace dronecore; | ||
|
||
#define ERROR_CONSOLE_TEXT "\033[31m" //Turn text on console red | ||
#define TELEMETRY_CONSOLE_TEXT "\033[34m" //Turn text on console blue | ||
#define NORMAL_CONSOLE_TEXT "\033[0m" //Restore normal console colour | ||
|
||
int main(int /*argc*/, char ** /*argv*/) | ||
{ | ||
DroneCore dc; | ||
|
||
bool discovered_device = false; | ||
|
||
DroneCore::ConnectionResult connection_result = dc.add_udp_connection(); | ||
|
||
if (connection_result != DroneCore::ConnectionResult::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Connection failed: " | ||
<< DroneCore::connection_result_str(connection_result) | ||
<< NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
std::cout << "Waiting to discover device..." << std::endl; | ||
dc.register_on_discover([&discovered_device](uint64_t uuid) { | ||
std::cout << "Discovered device with UUID: " << uuid << std::endl; | ||
discovered_device = true; | ||
}); | ||
|
||
// We usually receive heartbeats at 1Hz, therefore we should find a device after around 2 seconds. | ||
std::this_thread::sleep_for(std::chrono::seconds(2)); | ||
|
||
if (!discovered_device) { | ||
std::cout << ERROR_CONSOLE_TEXT << "No device found, exiting." << NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
// We don't need to specify the UUID if it's only one device anyway. | ||
// If there were multiple, we could specify it with: | ||
// dc.device(uint64_t uuid); | ||
Device &device = dc.device(); | ||
|
||
// We want to listen to the altitude of the drone at 1 Hz. | ||
const Telemetry::Result set_rate_result = dc.device().telemetry().set_rate_position(1.0); | ||
if (set_rate_result != Telemetry::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Setting rate failed:" << Telemetry::result_str( | ||
set_rate_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
|
||
// Set up callback to monitor altitude while the vehicle is in flight | ||
device.telemetry().position_async([](Telemetry::Position position) { | ||
std::cout << TELEMETRY_CONSOLE_TEXT // set to blue | ||
<< "Altitude: " << position.relative_altitude_m << " m" | ||
<< NORMAL_CONSOLE_TEXT // set to default color again | ||
<< std::endl; | ||
}); | ||
|
||
|
||
// Check if vehicle is ready to arm | ||
if (device.telemetry().health_all_ok() != true) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Vehicle not ready to arm" << NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
// Arm vehicle | ||
std::cout << "Arming..." << std::endl; | ||
const Action::Result arm_result = device.action().arm(); | ||
|
||
if (arm_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Arming failed:" << Action::result_str( | ||
arm_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
// Take off | ||
std::cout << "Taking off..." << std::endl; | ||
const Action::Result takeoff_result = device.action().takeoff(); | ||
if (takeoff_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Takeoff failed:" << Action::result_str( | ||
takeoff_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
return 1; | ||
} | ||
|
||
// Wait | ||
std::this_thread::sleep_for(std::chrono::seconds(10)); | ||
|
||
// Change to FW | ||
const Action::Result fw_result = device.action().transition_to_fixedwing(); | ||
|
||
if (fw_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Transition to fixed wing failed: " << Action::result_str( | ||
fw_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
//return 1; | ||
} | ||
|
||
// Wait | ||
std::this_thread::sleep_for(std::chrono::seconds(10)); | ||
|
||
// Change to VTOL | ||
const Action::Result mc_result = device.action().transition_to_multicopter(); | ||
if (mc_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Transition to multi copter failed:" << Action::result_str( | ||
mc_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
// return 1; | ||
} | ||
|
||
// Wait | ||
std::this_thread::sleep_for(std::chrono::seconds(5)); | ||
|
||
// Return to launch | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Actions in examples should be output to console rather than commented so that users have something to watch in the console. So "arming", "Taking off", "Landing", "Returning" etc. |
||
const Action::Result rtl_result = device.action().return_to_launch(); | ||
if (rtl_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Returning to launch failed:" << Action::result_str( | ||
rtl_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
// return 1; | ||
} | ||
|
||
// Wait | ||
std::this_thread::sleep_for(std::chrono::seconds(20)); | ||
|
||
// Land | ||
std::cout << "Landing..." << std::endl; | ||
const Action::Result land_result = device.action().land(); | ||
if (land_result != Action::Result::SUCCESS) { | ||
std::cout << ERROR_CONSOLE_TEXT << "Land failed:" << Action::result_str( | ||
land_result) << NORMAL_CONSOLE_TEXT << std::endl; | ||
// return 1; | ||
} | ||
|
||
// We are relying on auto-disarming but let's keep watching the telemetry for a bit longer. | ||
std::this_thread::sleep_for(std::chrono::seconds(5)); | ||
std::cout << "Finished..." << std::endl; | ||
return 0; | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -27,6 +27,7 @@ list(APPEND integration_tests | |
mission_survey | ||
gimbal | ||
curl | ||
transition_multicopter_fixedwing | ||
) | ||
|
||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,87 @@ | ||
#include <iostream> | ||
#include "integration_test_helper.h" | ||
#include "dronecore.h" | ||
|
||
using namespace dronecore; | ||
|
||
|
||
//static void connect(DroneCore); | ||
static void takeoff(Device &); | ||
static void takeoff_and_transition_to_fixedwing(); | ||
static void land_and_disarm(Device &); | ||
|
||
|
||
TEST_F(SitlTest, ActionSimpleTransition) | ||
{ | ||
takeoff_and_transition_to_fixedwing(); | ||
} | ||
|
||
void takeoff_and_transition_to_fixedwing() | ||
{ | ||
// Init & connect | ||
DroneCore dc; | ||
|
||
DroneCore::ConnectionResult ret = dc.add_udp_connection(); | ||
ASSERT_EQ(ret, DroneCore::ConnectionResult::SUCCESS); | ||
|
||
// Wait for device to connect via heartbeat. | ||
std::this_thread::sleep_for(std::chrono::seconds(2)); | ||
ASSERT_TRUE(dc.is_connected()); | ||
|
||
Device &device = dc.device(); | ||
|
||
// We need to takeoff first, otherwise we can't actually transition | ||
LogInfo() << "Taking off"; | ||
takeoff(device); | ||
|
||
LogInfo() << "Transitioning to fixedwing"; | ||
device.action().transition_to_fixedwing(); | ||
|
||
// Wait a little before the transition back to multicopter, | ||
// so we can actually see it fly | ||
std::this_thread::sleep_for(std::chrono::seconds(5)); | ||
|
||
LogInfo() << "Transitioning to multicopter"; | ||
device.action().transition_to_multicopter(); | ||
std::this_thread::sleep_for(std::chrono::seconds(5)); | ||
|
||
// Return safely to launch position so the next test | ||
// can start with a clean slate | ||
land_and_disarm(device); | ||
} | ||
|
||
void land_and_disarm(Device &device) | ||
{ | ||
device.action().return_to_launch(); | ||
|
||
// Wait until the vtol is disarmed. | ||
while (device.telemetry().armed()) { | ||
std::this_thread::sleep_for(std::chrono::seconds(1)); | ||
} | ||
LogInfo() << "Disarmed, exiting."; | ||
} | ||
|
||
void takeoff(Device &device) | ||
{ | ||
while (!device.telemetry().health_all_ok()) { | ||
std::cout << "waiting for device to be ready" << std::endl; | ||
std::this_thread::sleep_for(std::chrono::seconds(1)); | ||
} | ||
|
||
Action::Result action_ret = device.action().arm(); | ||
EXPECT_EQ(action_ret, Action::Result::SUCCESS); | ||
std::this_thread::sleep_for(std::chrono::seconds(1)); | ||
|
||
float altitude_m = 10.0f; | ||
device.action().set_takeoff_altitude(altitude_m); | ||
|
||
action_ret = device.action().takeoff(); | ||
EXPECT_EQ(action_ret, Action::Result::SUCCESS); | ||
const int wait_time_s = 10; | ||
std::this_thread::sleep_for(std::chrono::seconds(wait_time_s)); | ||
|
||
|
||
EXPECT_GT(device.telemetry().position().relative_altitude_m, altitude_m - 0.25f); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nice check, that will be useful once these integration tests make it into the PX4 Firmware testing. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks, but I have to give credit where due. I got it from the simple_hover example ;) |
||
EXPECT_LT(device.telemetry().position().relative_altitude_m, altitude_m + 0.25f); | ||
} | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -118,6 +118,26 @@ class Action | |
*/ | ||
Result return_to_launch() const; | ||
|
||
/** | ||
* @brief Send command to transition the drone to fixedwing. | ||
* | ||
* The associated action will only be executed for VTOL vehicles in multicopter mode. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks! This will need to be checked of course (once we have got the timeout issue fix). It may be that PX4 would simply ignore the command if sent while already in the current mode (rather than fail) and similarly it might ignore the command for non vtol rather than failing it. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @julianoes So based on your change PX4/PX4-Autopilot#8264 would I be correct in saying that
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
correct, it will just succeed.
It will just time out because the VTOL controller is not running and therefore not responding. A check to see if it is actually a VTOL and a specific error message for it would be nice! There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @xgerrmann So
@julianoes What about if someone is using firmware pre your fix? Should we also have a PX4 version check? |
||
* On other vehicles/modes the command will fail with a Result. | ||
* | ||
* @return Result of request. | ||
*/ | ||
Result transition_to_fixedwing() const; | ||
|
||
/** | ||
* @brief Send command to transition the drone to multicopter. | ||
* | ||
* The associated action will only be executed for VTOL vehicles in fixedwing mode. | ||
* On other vehicles/modes the command will fail with a Result. | ||
* | ||
* @return Result of request. | ||
*/ | ||
Result transition_to_multicopter() const; | ||
|
||
/** | ||
* @brief Callback type for asynchronous Action calls. | ||
*/ | ||
|
@@ -186,6 +206,26 @@ class Action | |
*/ | ||
void return_to_launch_async(result_callback_t callback); | ||
|
||
/** | ||
* @brief Send command to transition the drone to fixedwing (asynchronous). | ||
* | ||
* Note that this is only for the vtol type. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Argg, my comment from yesterday lost. Can you check your email for my suggested wording? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Found it :) Next commit will include your comment. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks. Looks good. We will need to test that the comment is actually true once the timeout is fixed :-) |
||
* Also, transition to fixedwing is only allowed from multicopter. | ||
* | ||
* @param callback Function to call with result of request. | ||
*/ | ||
void transition_to_fixedwing_async(result_callback_t callback); | ||
|
||
/** | ||
* @brief Send command to transition the drone to multicopter (asynchronous). | ||
* | ||
* Note that this is only for the vtol type. | ||
* Also, transition to fixedwing is only allowed from multicopter. | ||
* | ||
* @param callback Function to call with result of request. | ||
*/ | ||
void transition_to_multicopter_async(result_callback_t callback); | ||
|
||
/** | ||
* @brief Set takeoff altitude above ground. | ||
* | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Once you merge or rebase you will see that this file gets a lot simpler.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The required changes are being documented in mavlink/MAVSDK-docs#62 (in progress). The interesting bit is here - basically we're changing to use system-wide install by default AND dronecore itself is now linking to the thread library - so you no longer need to do most of this work.