mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
[FlightTasks] Added class enum for FlightTasks errors (#12822)
This commit is contained in:
@@ -57,11 +57,11 @@ const landing_gear_s FlightTasks::getGear()
|
||||
}
|
||||
}
|
||||
|
||||
int FlightTasks::switchTask(FlightTaskIndex new_task_index)
|
||||
FlightTaskError FlightTasks::switchTask(FlightTaskIndex new_task_index)
|
||||
{
|
||||
// switch to the running task, nothing to do
|
||||
if (new_task_index == _current_task.index) {
|
||||
return 0;
|
||||
return FlightTaskError::NoError;
|
||||
}
|
||||
|
||||
// Save current setpoints for the nex FlightTask
|
||||
@@ -69,12 +69,12 @@ int FlightTasks::switchTask(FlightTaskIndex new_task_index)
|
||||
|
||||
if (_initTask(new_task_index)) {
|
||||
// invalid task
|
||||
return -1;
|
||||
return FlightTaskError::InvalidTask;
|
||||
}
|
||||
|
||||
if (!_current_task.task) {
|
||||
// no task running
|
||||
return 0;
|
||||
return FlightTaskError::NoError;
|
||||
}
|
||||
|
||||
// subscription failed
|
||||
@@ -82,7 +82,7 @@ int FlightTasks::switchTask(FlightTaskIndex new_task_index)
|
||||
_current_task.task->~FlightTask();
|
||||
_current_task.task = nullptr;
|
||||
_current_task.index = FlightTaskIndex::None;
|
||||
return -2;
|
||||
return FlightTaskError::SubscriptionFailed;
|
||||
}
|
||||
|
||||
_subscription_array.forcedUpdate(); // make sure data is available for all new subscriptions
|
||||
@@ -92,13 +92,13 @@ int FlightTasks::switchTask(FlightTaskIndex new_task_index)
|
||||
_current_task.task->~FlightTask();
|
||||
_current_task.task = nullptr;
|
||||
_current_task.index = FlightTaskIndex::None;
|
||||
return -3;
|
||||
return FlightTaskError::ActivationFailed;
|
||||
}
|
||||
|
||||
return 0;
|
||||
return FlightTaskError::NoError;
|
||||
}
|
||||
|
||||
int FlightTasks::switchTask(int new_task_index)
|
||||
FlightTaskError FlightTasks::switchTask(int new_task_index)
|
||||
{
|
||||
// make sure we are in range of the enumeration before casting
|
||||
if (static_cast<int>(FlightTaskIndex::None) <= new_task_index &&
|
||||
@@ -107,7 +107,7 @@ int FlightTasks::switchTask(int new_task_index)
|
||||
}
|
||||
|
||||
switchTask(FlightTaskIndex::None);
|
||||
return -1;
|
||||
return FlightTaskError::InvalidTask;
|
||||
}
|
||||
|
||||
void FlightTasks::handleParameterUpdate()
|
||||
@@ -117,10 +117,10 @@ void FlightTasks::handleParameterUpdate()
|
||||
}
|
||||
}
|
||||
|
||||
const char *FlightTasks::errorToString(const int error)
|
||||
const char *FlightTasks::errorToString(const FlightTaskError error)
|
||||
{
|
||||
for (auto e : _taskError) {
|
||||
if (e.error == error) {
|
||||
if (static_cast<FlightTaskError>(e.error) == error) {
|
||||
return e.msg;
|
||||
}
|
||||
}
|
||||
@@ -157,11 +157,11 @@ void FlightTasks::_updateCommand()
|
||||
}
|
||||
|
||||
// switch to the commanded task
|
||||
int switch_result = switchTask(desired_task);
|
||||
FlightTaskError switch_result = switchTask(desired_task);
|
||||
uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
|
||||
|
||||
// if we are in/switched to the desired task
|
||||
if (switch_result >= 0) {
|
||||
if (switch_result >= FlightTaskError::NoError) {
|
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
|
||||
|
||||
// if the task is running apply parameters to it and see if it rejects
|
||||
@@ -169,7 +169,7 @@ void FlightTasks::_updateCommand()
|
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
|
||||
|
||||
// if we just switched and parameters are not accepted, go to failsafe
|
||||
if (switch_result == 1) {
|
||||
if (switch_result >= FlightTaskError::NoError) {
|
||||
switchTask(FlightTaskIndex::ManualPosition);
|
||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
|
||||
}
|
||||
@@ -181,7 +181,7 @@ void FlightTasks::_updateCommand()
|
||||
command_ack.timestamp = hrt_absolute_time();
|
||||
command_ack.command = command.command;
|
||||
command_ack.result = cmd_result;
|
||||
command_ack.result_param1 = switch_result;
|
||||
command_ack.result_param1 = static_cast<int>(switch_result);
|
||||
command_ack.target_system = command.source_system;
|
||||
command_ack.target_component = command.source_component;
|
||||
|
||||
|
||||
@@ -52,6 +52,13 @@
|
||||
|
||||
#include <new>
|
||||
|
||||
enum class FlightTaskError : int {
|
||||
NoError = 0,
|
||||
InvalidTask = -1,
|
||||
SubscriptionFailed = -2,
|
||||
ActivationFailed = -3
|
||||
};
|
||||
|
||||
class FlightTasks
|
||||
{
|
||||
public:
|
||||
@@ -102,17 +109,17 @@ public:
|
||||
|
||||
/**
|
||||
* Switch to the next task in the available list (for testing)
|
||||
* @return 1 on success, <0 on error
|
||||
* @return 0 on success, <0 on error
|
||||
*/
|
||||
int switchTask() { return switchTask(static_cast<int>(_current_task.index) + 1); }
|
||||
FlightTaskError switchTask() { return switchTask(static_cast<int>(_current_task.index) + 1); }
|
||||
|
||||
/**
|
||||
* Switch to a specific task (for normal usage)
|
||||
* @param task index to switch to
|
||||
* @return 1 on success, 0 on no change, <0 on error
|
||||
* @return 0 on success, <0 on error
|
||||
*/
|
||||
int switchTask(FlightTaskIndex new_task_index);
|
||||
int switchTask(int new_task_index);
|
||||
FlightTaskError switchTask(FlightTaskIndex new_task_index);
|
||||
FlightTaskError switchTask(int new_task_index);
|
||||
|
||||
/**
|
||||
* Get the number of the active task
|
||||
@@ -134,7 +141,7 @@ public:
|
||||
/**
|
||||
* Call this method to get the description of a task error.
|
||||
*/
|
||||
const char *errorToString(const int error);
|
||||
const char *errorToString(const FlightTaskError error);
|
||||
|
||||
/**
|
||||
* Sets an external yaw handler. The active flight task can use the yaw handler to implement a different yaw control strategy.
|
||||
@@ -174,10 +181,10 @@ private:
|
||||
* Map from Error int to user friendly string.
|
||||
*/
|
||||
task_error_t _taskError[_numError] = {
|
||||
{0, "No Error"},
|
||||
{-1, "Invalid Task "},
|
||||
{-2, "Subscription Failed"},
|
||||
{-3, "Activation Failed"}
|
||||
{static_cast<int>(FlightTaskError::NoError), "No Error"},
|
||||
{static_cast<int>(FlightTaskError::InvalidTask), "Invalid Task "},
|
||||
{static_cast<int>(FlightTaskError::SubscriptionFailed), "Subscription Failed"},
|
||||
{static_cast<int>(FlightTaskError::ActivationFailed), "Activation Failed"}
|
||||
};
|
||||
/**
|
||||
* Check for vehicle commands (received via MAVLink), evaluate and acknowledge them
|
||||
|
||||
@@ -739,9 +739,9 @@ MulticopterPositionControl::start_flight_task()
|
||||
|
||||
if (_vehicle_status.in_transition_mode) {
|
||||
should_disable_task = false;
|
||||
int error = _flight_tasks.switchTask(FlightTaskIndex::Transition);
|
||||
FlightTaskError error = _flight_tasks.switchTask(FlightTaskIndex::Transition);
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Transition activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -766,9 +766,9 @@ MulticopterPositionControl::start_flight_task()
|
||||
_control_mode.flag_control_acceleration_enabled)) {
|
||||
|
||||
should_disable_task = false;
|
||||
int error = _flight_tasks.switchTask(FlightTaskIndex::Offboard);
|
||||
FlightTaskError error = _flight_tasks.switchTask(FlightTaskIndex::Offboard);
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Offboard activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -785,9 +785,9 @@ MulticopterPositionControl::start_flight_task()
|
||||
// Auto-follow me
|
||||
if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET) {
|
||||
should_disable_task = false;
|
||||
int error = _flight_tasks.switchTask(FlightTaskIndex::AutoFollowMe);
|
||||
FlightTaskError error = _flight_tasks.switchTask(FlightTaskIndex::AutoFollowMe);
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Follow-Me activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -803,7 +803,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
} else if (_control_mode.flag_control_auto_enabled) {
|
||||
// Auto related maneuvers
|
||||
should_disable_task = false;
|
||||
int error = 0;
|
||||
FlightTaskError error = FlightTaskError::NoError;
|
||||
|
||||
switch (_param_mpc_auto_mode.get()) {
|
||||
case 1:
|
||||
@@ -815,7 +815,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
break;
|
||||
}
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Auto activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -832,7 +832,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
// manual position control
|
||||
if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL || task_failure) {
|
||||
should_disable_task = false;
|
||||
int error = 0;
|
||||
FlightTaskError error = FlightTaskError::NoError;
|
||||
|
||||
switch (_param_mpc_pos_mode.get()) {
|
||||
case 1:
|
||||
@@ -852,7 +852,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
break;
|
||||
}
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Position-Ctrl activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -869,7 +869,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
// manual altitude control
|
||||
if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL || task_failure) {
|
||||
should_disable_task = false;
|
||||
int error = 0;
|
||||
FlightTaskError error = FlightTaskError::NoError;
|
||||
|
||||
switch (_param_mpc_pos_mode.get()) {
|
||||
case 1:
|
||||
@@ -885,7 +885,7 @@ MulticopterPositionControl::start_flight_task()
|
||||
break;
|
||||
}
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
if (prev_failure_count == 0) {
|
||||
PX4_WARN("Altitude-Ctrl activation failed with error: %s", _flight_tasks.errorToString(error));
|
||||
}
|
||||
@@ -908,9 +908,9 @@ MulticopterPositionControl::start_flight_task()
|
||||
|
||||
// for some reason no flighttask was able to start.
|
||||
// go into failsafe flighttask
|
||||
int error = _flight_tasks.switchTask(FlightTaskIndex::Failsafe);
|
||||
FlightTaskError error = _flight_tasks.switchTask(FlightTaskIndex::Failsafe);
|
||||
|
||||
if (error != 0) {
|
||||
if (error != FlightTaskError::NoError) {
|
||||
// No task was activated.
|
||||
_flight_tasks.switchTask(FlightTaskIndex::None);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user