Skip to content
Snippets Groups Projects
Commit 8b4471d8 authored by Matthias Grob's avatar Matthias Grob Committed by Beat Küng
Browse files

FlightTasks: comment out mavlink command processing

because upstream there needs to be a
common mavlink command definition first
and then it can be easily reenabled again
parent cf48ceb4
No related branches found
No related tags found
No related merge requests found
...@@ -113,62 +113,63 @@ int FlightTasks::switchTask(int new_task_index) ...@@ -113,62 +113,63 @@ int FlightTasks::switchTask(int new_task_index)
void FlightTasks::_updateCommand() void FlightTasks::_updateCommand()
{ {
/* lazy subscription to command topic */ // TODO: port flight task mavlink command to have support for this functionality
if (_sub_vehicle_command < 0) { // /* lazy subscription to command topic */
_sub_vehicle_command = orb_subscribe(ORB_ID(vehicle_command)); // if (_sub_vehicle_command < 0) {
} // _sub_vehicle_command = orb_subscribe(ORB_ID(vehicle_command));
// }
/* check if there's any new command */ //
bool updated = false; // /* check if there's any new command */
orb_check(_sub_vehicle_command, &updated); // bool updated = false;
// orb_check(_sub_vehicle_command, &updated);
if (!updated) { //
return; // if (!updated) {
} // return;
// }
/* check if command is for flight task library */ //
struct vehicle_command_s command; // /* check if command is for flight task library */
orb_copy(ORB_ID(vehicle_command), _sub_vehicle_command, &command); // struct vehicle_command_s command;
// orb_copy(ORB_ID(vehicle_command), _sub_vehicle_command, &command);
if (command.command != vehicle_command_s::VEHICLE_CMD_FLIGHT_TASK) { //
return; // if (command.command != vehicle_command_s::VEHICLE_CMD_FLIGHT_TASK) {
} // return;
// }
/* evaluate command */ //
// TODO: remapping of the Mavlink definition to the internal tasks necessary // /* evaluate command */
int switch_result = switchTask(int(command.param1 + 0.5f)); // // TODO: remapping of the Mavlink definition to the internal tasks necessary
uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED; // int switch_result = switchTask(int(command.param1 + 0.5f));
// uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
/* if we are in the desired task */ //
if (switch_result >= 0) { // /* if we are in the desired task */
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED; // if (switch_result >= 0) {
// cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
/* if the task is running apply parameters to it and see if it rejects */ //
if (isAnyTaskActive() && !_current_task->applyCommandParameters(command)) { // /* if the task is running apply parameters to it and see if it rejects */
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED; // if (isAnyTaskActive() && !_current_task->applyCommandParameters(command)) {
// 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 we just switched and parameters are not accepted, go to failsafe */
switchTask(-1); // if (switch_result == 1) {
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED; // switchTask(-1);
} // cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
} // }
} // }
// }
/* send back acknowledgment */ //
vehicle_command_ack_s command_ack = {}; // /* send back acknowledgment */
command_ack.command = command.command; // vehicle_command_ack_s command_ack = {};
command_ack.result = cmd_result; // command_ack.command = command.command;
command_ack.result_param1 = switch_result; // command_ack.result = cmd_result;
command_ack.target_system = command.source_system; // command_ack.result_param1 = switch_result;
command_ack.target_component = command.source_component; // command_ack.target_system = command.source_system;
// command_ack.target_component = command.source_component;
if (_pub_vehicle_command_ack == nullptr) { //
_pub_vehicle_command_ack = orb_advertise_queue(ORB_ID(vehicle_command_ack), &command_ack, // if (_pub_vehicle_command_ack == nullptr) {
vehicle_command_ack_s::ORB_QUEUE_LENGTH); // _pub_vehicle_command_ack = orb_advertise_queue(ORB_ID(vehicle_command_ack), &command_ack,
// vehicle_command_ack_s::ORB_QUEUE_LENGTH);
} else { //
orb_publish(ORB_ID(vehicle_command_ack), _pub_vehicle_command_ack, &command_ack); // } else {
// orb_publish(ORB_ID(vehicle_command_ack), _pub_vehicle_command_ack, &command_ack);
} //
// }
} }
...@@ -152,6 +152,6 @@ private: ...@@ -152,6 +152,6 @@ private:
* Check for vehicle commands (received via MAVLink), evaluate and acknowledge them * Check for vehicle commands (received via MAVLink), evaluate and acknowledge them
*/ */
void _updateCommand(); void _updateCommand();
int _sub_vehicle_command = -1; /**< topic handle on which commands are received */ // int _sub_vehicle_command = -1; /**< topic handle on which commands are received */
orb_advert_t _pub_vehicle_command_ack = nullptr; /**< topic handle to which commands get acknowledged */ // orb_advert_t _pub_vehicle_command_ack = nullptr; /**< topic handle to which commands get acknowledged */
}; };
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment