2012-08-04 15:12:36 -07:00
/****************************************************************************
*
2013-06-25 13:15:38 +02:00
* Copyright ( C ) 2013 PX4 Development Team . All rights reserved .
2012-10-23 13:15:36 +02:00
* Author : Petri Tanskanen < petri . tanskanen @ inf . ethz . ch >
* Lorenz Meier < lm @ inf . ethz . ch >
* Thomas Gubler < thomasgubler @ student . ethz . ch >
* Julian Oes < joes @ student . ethz . ch >
2012-08-04 15:12:36 -07: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 .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
2013-07-20 13:47:51 +02:00
* @ file commander . cpp
2012-08-04 15:12:36 -07:00
* Main system state machine implementation .
2012-10-23 13:15:36 +02:00
*
2012-08-04 15:12:36 -07:00
*/
# include <nuttx/config.h>
# include <pthread.h>
# include <stdio.h>
# include <stdlib.h>
# include <stdbool.h>
# include <string.h>
# include <unistd.h>
# include <fcntl.h>
# include <errno.h>
# include <debug.h>
# include <sys/prctl.h>
2013-08-17 15:47:42 +02:00
# include <sys/stat.h>
2012-08-04 15:12:36 -07:00
# include <string.h>
# include <math.h>
# include <poll.h>
2013-03-11 10:39:57 -07:00
2012-08-04 15:12:36 -07:00
# include <uORB/uORB.h>
# include <uORB/topics/sensor_combined.h>
2013-01-01 13:30:24 +01:00
# include <uORB/topics/battery_status.h>
2012-09-21 12:55:41 +02:00
# include <uORB/topics/manual_control_setpoint.h>
# include <uORB/topics/offboard_control_setpoint.h>
2013-01-19 14:46:26 +01:00
# include <uORB/topics/home_position.h>
2012-12-13 10:23:02 +01:00
# include <uORB/topics/vehicle_global_position.h>
# include <uORB/topics/vehicle_local_position.h>
2013-01-19 14:46:26 +01:00
# include <uORB/topics/vehicle_gps_position.h>
2012-08-04 15:12:36 -07:00
# include <uORB/topics/vehicle_command.h>
2013-06-14 13:53:26 +02:00
# include <uORB/topics/vehicle_control_mode.h>
2012-08-24 00:01:23 +02:00
# include <uORB/topics/subsystem_info.h>
2012-09-05 11:37:17 +02:00
# include <uORB/topics/actuator_controls.h>
2013-07-15 22:15:15 +02:00
# include <uORB/topics/actuator_armed.h>
2012-12-13 10:23:02 +01:00
# include <uORB/topics/parameter_update.h>
2013-02-24 21:57:38 +01:00
# include <uORB/topics/differential_pressure.h>
2013-07-15 22:15:15 +02:00
# include <uORB/topics/safety.h>
2012-09-25 10:31:19 +02:00
2013-03-11 10:39:57 -07:00
# include <drivers/drv_led.h>
# include <drivers/drv_hrt.h>
# include <drivers/drv_tone_alarm.h>
# include <mavlink/mavlink_log.h>
2012-08-20 23:52:13 +02:00
# include <systemlib/param/param.h>
2012-08-04 15:12:36 -07:00
# include <systemlib/systemlib.h>
2012-09-11 23:35:01 +02:00
# include <systemlib/err.h>
2013-03-11 10:39:57 -07:00
# include <systemlib/cpuload.h>
2013-08-14 10:59:22 +02:00
# include "px4_custom_mode.h"
2013-06-25 16:30:35 +02:00
# include "commander_helper.h"
2013-03-11 10:39:57 -07:00
# include "state_machine_helper.h"
2012-10-21 15:36:29 +02:00
# include "calibration_routines.h"
2013-04-25 23:59:46 +04:00
# include "accelerometer_calibration.h"
2013-06-25 16:30:35 +02:00
# include "gyro_calibration.h"
# include "mag_calibration.h"
# include "baro_calibration.h"
# include "rc_calibration.h"
# include "airspeed_calibration.h"
2012-09-11 23:35:01 +02:00
2013-07-20 13:47:51 +02:00
/* oddly, ERROR is not defined for c++ */
# ifdef ERROR
# undef ERROR
# endif
static const int ERROR = - 1 ;
2013-03-11 10:39:57 -07:00
2012-08-04 15:12:36 -07:00
extern struct system_load_s system_load ;
2013-06-25 16:30:35 +02:00
# define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
# define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
2012-08-04 15:12:36 -07:00
/* Decouple update interval and hysteris counters, all depends on intervals */
# define COMMANDER_MONITORING_INTERVAL 50000
# define COMMANDER_MONITORING_LOOPSPERMSEC (1 / (COMMANDER_MONITORING_INTERVAL / 1000.0f))
# define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
# define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
2012-09-21 12:55:41 +02:00
# define STICK_ON_OFF_LIMIT 0.75f
# define STICK_THRUST_RANGE 1.0f
2012-08-04 15:12:36 -07:00
# define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
# define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
# define GPS_FIX_TYPE_2D 2
# define GPS_FIX_TYPE_3D 3
2012-09-21 12:55:41 +02:00
# define GPS_QUALITY_GOOD_HYSTERIS_TIME_MS 5000
# define GPS_QUALITY_GOOD_COUNTER_LIMIT (GPS_QUALITY_GOOD_HYSTERIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
2012-08-04 15:12:36 -07:00
2013-03-11 10:39:57 -07:00
# define LOCAL_POSITION_TIMEOUT 1000000 /**< consider the local position estimate invalid after 1s */
2013-07-31 20:58:27 +04:00
# define PRINT_INTERVAL 5000000
# define PRINT_MODE_REJECT_INTERVAL 2000000
enum MAV_MODE_FLAG {
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 , /* 0b00000001 Reserved for future use. | */
MAV_MODE_FLAG_TEST_ENABLED = 2 , /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
MAV_MODE_FLAG_AUTO_ENABLED = 4 , /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
MAV_MODE_FLAG_GUIDED_ENABLED = 8 , /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
MAV_MODE_FLAG_STABILIZE_ENABLED = 16 , /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
MAV_MODE_FLAG_HIL_ENABLED = 32 , /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 , /* 0b01000000 remote control input is enabled. | */
MAV_MODE_FLAG_SAFETY_ARMED = 128 , /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
MAV_MODE_FLAG_ENUM_END = 129 , /* | */
} ;
2013-08-07 20:21:49 +02:00
2013-07-16 09:24:21 +02:00
/* Mavlink file descriptors */
2012-08-04 15:12:36 -07:00
static int mavlink_fd ;
2013-02-16 13:40:09 -08:00
/* flags */
2012-08-04 15:12:36 -07:00
static bool commander_initialized = false ;
2013-02-16 13:40:09 -08:00
static bool thread_should_exit = false ; /**< daemon exit flag */
static bool thread_running = false ; /**< daemon status flag */
static int daemon_task ; /**< Handle of daemon task / thread */
2013-03-25 14:53:54 -07:00
/* timout until lowlevel failsafe */
2012-09-21 12:55:41 +02:00
static unsigned int failsafe_lowlevel_timeout_ms ;
2013-07-31 20:58:27 +04:00
static unsigned int leds_counter ;
/* To remember when last notification was sent */
static uint64_t last_print_mode_reject_time = 0 ;
2013-08-17 15:47:42 +02:00
/* if connected via USB */
static bool on_usb_power = false ;
2013-07-31 20:58:27 +04:00
2012-09-21 12:55:41 +02:00
2013-03-25 14:53:54 -07:00
/* tasks waiting for low prio thread */
2013-07-31 20:58:27 +04:00
typedef enum {
2013-03-25 14:53:54 -07:00
LOW_PRIO_TASK_NONE = 0 ,
LOW_PRIO_TASK_PARAM_SAVE ,
LOW_PRIO_TASK_PARAM_LOAD ,
LOW_PRIO_TASK_GYRO_CALIBRATION ,
LOW_PRIO_TASK_MAG_CALIBRATION ,
LOW_PRIO_TASK_ALTITUDE_CALIBRATION ,
LOW_PRIO_TASK_RC_CALIBRATION ,
LOW_PRIO_TASK_ACCEL_CALIBRATION ,
LOW_PRIO_TASK_AIRSPEED_CALIBRATION
2013-07-31 20:58:27 +04:00
} low_prio_task_t ;
2013-03-25 14:53:54 -07:00
2013-07-31 20:58:27 +04:00
static low_prio_task_t low_prio_task = LOW_PRIO_TASK_NONE ;
2012-08-04 15:12:36 -07:00
2013-07-16 09:24:21 +02:00
/**
2013-07-16 09:35:31 +02:00
* The daemon app only briefly exists to start
* the background job . The stack size assigned in the
* Makefile does only apply to this management task .
*
* The actual stack size should be set in the call
* to task_create ( ) .
2013-07-20 13:47:51 +02:00
*
* @ ingroup apps
2013-07-16 09:24:21 +02:00
*/
2013-07-20 13:47:51 +02:00
extern " C " __EXPORT int commander_main ( int argc , char * argv [ ] ) ;
2012-08-04 15:12:36 -07:00
2012-08-20 23:52:13 +02:00
/**
2013-07-16 09:35:31 +02:00
* Print the correct usage .
2012-08-20 23:52:13 +02:00
*/
2013-07-16 09:35:31 +02:00
void usage ( const char * reason ) ;
2012-08-20 23:52:13 +02:00
2013-07-16 09:24:21 +02:00
/**
* React to commands that are sent e . g . from the mavlink module .
*/
2013-07-31 20:58:27 +04:00
void handle_command ( struct vehicle_status_s * status , struct vehicle_control_mode_s * control_mode , struct vehicle_command_s * cmd , struct actuator_armed_s * armed ) ;
2012-08-20 23:52:13 +02:00
/**
2013-07-16 09:35:31 +02:00
* Mainloop of commander .
2012-08-20 23:52:13 +02:00
*/
2013-07-16 09:35:31 +02:00
int commander_thread_main ( int argc , char * argv [ ] ) ;
2013-08-16 18:05:59 +02:00
void toggle_status_leds ( vehicle_status_s * status , actuator_armed_s * armed , bool changed ) ;
2013-07-31 20:58:27 +04:00
2013-07-28 23:12:16 +04:00
void check_mode_switches ( struct manual_control_setpoint_s * sp_man , struct vehicle_status_s * current_status ) ;
transition_result_t check_main_state_machine ( struct vehicle_status_s * current_status ) ;
2013-07-31 20:58:27 +04:00
void print_reject_mode ( const char * msg ) ;
2013-08-17 15:47:42 +02:00
void print_status ( ) ;
2013-07-28 23:12:16 +04:00
transition_result_t check_navigation_state_machine ( struct vehicle_status_s * current_status , struct vehicle_control_mode_s * control_mode ) ;
2013-07-16 09:35:31 +02:00
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks .
*/
void * commander_low_prio_loop ( void * arg ) ;
int commander_main ( int argc , char * argv [ ] )
{
if ( argc < 1 )
usage ( " missing command " ) ;
if ( ! strcmp ( argv [ 1 ] , " start " ) ) {
if ( thread_running ) {
warnx ( " commander already running \n " ) ;
/* this is not an error */
exit ( 0 ) ;
}
thread_should_exit = false ;
daemon_task = task_spawn_cmd ( " commander " ,
2013-07-28 23:12:16 +04:00
SCHED_DEFAULT ,
SCHED_PRIORITY_MAX - 40 ,
3000 ,
commander_thread_main ,
( argv ) ? ( const char * * ) & argv [ 2 ] : ( const char * * ) NULL ) ;
2013-07-16 09:35:31 +02:00
exit ( 0 ) ;
}
2012-08-04 15:12:36 -07:00
2013-07-16 09:35:31 +02:00
if ( ! strcmp ( argv [ 1 ] , " stop " ) ) {
thread_should_exit = true ;
exit ( 0 ) ;
}
2013-03-25 14:53:54 -07:00
2013-07-16 09:35:31 +02:00
if ( ! strcmp ( argv [ 1 ] , " status " ) ) {
if ( thread_running ) {
warnx ( " \t commander is running \n " ) ;
2013-08-17 15:47:42 +02:00
print_status ( ) ;
2013-07-16 09:35:31 +02:00
} else {
warnx ( " \t commander not started \n " ) ;
}
exit ( 0 ) ;
}
usage ( " unrecognized command " ) ;
exit ( 1 ) ;
}
void usage ( const char * reason )
{
if ( reason )
fprintf ( stderr , " %s \n " , reason ) ;
fprintf ( stderr , " usage: daemon {start|stop|status} [-p <additional params>] \n \n " ) ;
exit ( 1 ) ;
}
2013-02-24 21:57:38 +01:00
2013-08-17 15:47:42 +02:00
void print_status ( ) {
warnx ( " usb powered: %s " , ( on_usb_power ) ? " yes " : " no " ) ;
}
2013-08-15 09:52:22 +02:00
void handle_command ( struct vehicle_status_s * status , const struct safety_s * safety , struct vehicle_control_mode_s * control_mode , struct vehicle_command_s * cmd , struct actuator_armed_s * armed )
2012-08-04 15:12:36 -07:00
{
/* result of the command */
2012-12-30 11:01:09 +01:00
uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED ;
2012-08-04 15:12:36 -07:00
/* request to set different system mode */
switch ( cmd - > command ) {
2013-07-31 20:58:27 +04:00
case VEHICLE_CMD_DO_SET_MODE : {
2013-08-07 20:21:49 +02:00
uint8_t base_mode = ( uint8_t ) cmd - > param1 ;
uint32_t custom_mode = ( uint32_t ) cmd - > param2 ;
2013-07-31 20:58:27 +04:00
// TODO remove debug code
mavlink_log_critical ( mavlink_fd , " [cmd] command setmode: %d %d " , base_mode , custom_mode ) ;
/* set arming state */
transition_result_t arming_res = TRANSITION_NOT_CHANGED ;
if ( base_mode & MAV_MODE_FLAG_SAFETY_ARMED ) {
2013-08-15 09:52:22 +02:00
arming_res = arming_state_transition ( status , safety , ARMING_STATE_ARMED , armed ) ;
2013-08-07 20:21:49 +02:00
2013-07-31 20:58:27 +04:00
if ( arming_res = = TRANSITION_CHANGED ) {
mavlink_log_info ( mavlink_fd , " [cmd] ARMED by command " ) ;
}
2012-08-08 18:47:46 +02:00
2013-07-31 20:58:27 +04:00
} else {
if ( status - > arming_state = = ARMING_STATE_ARMED | | status - > arming_state = = ARMING_STATE_ARMED_ERROR ) {
arming_state_t new_arming_state = ( status - > arming_state = = ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR ) ;
2013-08-15 09:52:22 +02:00
arming_res = arming_state_transition ( status , safety , new_arming_state , armed ) ;
2013-08-07 20:21:49 +02:00
2013-07-31 20:58:27 +04:00
if ( arming_res = = TRANSITION_CHANGED ) {
mavlink_log_info ( mavlink_fd , " [cmd] DISARMED by command " ) ;
}
2013-08-07 20:21:49 +02:00
2013-07-31 20:58:27 +04:00
} else {
arming_res = TRANSITION_NOT_CHANGED ;
}
}
2012-08-13 18:53:37 +02:00
2013-07-31 20:58:27 +04:00
/* set main state */
transition_result_t main_res = TRANSITION_DENIED ;
2012-08-04 15:12:36 -07:00
2013-08-07 20:21:49 +02:00
if ( base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED ) {
/* use autopilot-specific mode */
if ( custom_mode = = PX4_CUSTOM_MODE_MANUAL ) {
/* MANUAL */
main_res = main_state_transition ( status , MAIN_STATE_MANUAL ) ;
} else if ( custom_mode = = PX4_CUSTOM_MODE_SEATBELT ) {
/* SEATBELT */
main_res = main_state_transition ( status , MAIN_STATE_SEATBELT ) ;
2012-12-27 17:13:48 +01:00
2013-08-07 20:21:49 +02:00
} else if ( custom_mode = = PX4_CUSTOM_MODE_EASY ) {
2013-07-31 20:58:27 +04:00
/* EASY */
main_res = main_state_transition ( status , MAIN_STATE_EASY ) ;
2012-12-27 17:13:48 +01:00
2013-08-07 20:21:49 +02:00
} else if ( custom_mode = = PX4_CUSTOM_MODE_AUTO ) {
/* AUTO */
main_res = main_state_transition ( status , MAIN_STATE_AUTO ) ;
}
2013-07-28 23:12:16 +04:00
2013-08-07 20:21:49 +02:00
} else {
/* use base mode */
if ( base_mode & MAV_MODE_FLAG_AUTO_ENABLED ) {
/* AUTO */
main_res = main_state_transition ( status , MAIN_STATE_AUTO ) ;
} else if ( base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED ) {
if ( base_mode & MAV_MODE_FLAG_GUIDED_ENABLED ) {
/* EASY */
main_res = main_state_transition ( status , MAIN_STATE_EASY ) ;
} else if ( base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED ) {
2013-07-31 20:58:27 +04:00
/* MANUAL */
main_res = main_state_transition ( status , MAIN_STATE_MANUAL ) ;
}
2013-02-19 12:32:47 -08:00
}
2013-07-31 20:58:27 +04:00
}
if ( arming_res ! = TRANSITION_DENIED & & main_res ! = TRANSITION_DENIED ) {
result = VEHICLE_CMD_RESULT_ACCEPTED ;
2012-08-29 14:20:55 +02:00
2013-07-28 23:12:16 +04:00
} else {
result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2012-08-04 15:12:36 -07:00
}
2013-07-31 20:58:27 +04:00
break ;
}
2012-11-02 15:21:37 +01:00
2013-07-31 20:58:27 +04:00
case VEHICLE_CMD_COMPONENT_ARM_DISARM :
break ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN :
2013-08-15 09:52:22 +02:00
if ( is_safe ( status , safety , armed ) ) {
if ( ( ( int ) ( cmd - > param1 ) ) = = 1 ) {
/* reboot */
2013-08-15 14:04:46 +02:00
systemreset ( false ) ;
2013-08-15 09:52:22 +02:00
} else if ( ( ( int ) ( cmd - > param1 ) ) = = 3 ) {
/* reboot to bootloader */
// XXX implement
result = VEHICLE_CMD_RESULT_UNSUPPORTED ;
} else {
result = VEHICLE_CMD_RESULT_DENIED ;
}
} else {
result = VEHICLE_CMD_RESULT_DENIED ;
}
2013-07-31 20:58:27 +04:00
break ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
case VEHICLE_CMD_PREFLIGHT_CALIBRATION : {
low_prio_task_t new_low_prio_task = LOW_PRIO_TASK_NONE ;
2012-11-02 15:21:37 +01:00
2013-07-31 20:58:27 +04:00
if ( ( int ) ( cmd - > param1 ) = = 1 ) {
/* gyro calibration */
new_low_prio_task = LOW_PRIO_TASK_GYRO_CALIBRATION ;
2013-02-19 12:32:47 -08:00
2013-07-31 20:58:27 +04:00
} else if ( ( int ) ( cmd - > param2 ) = = 1 ) {
/* magnetometer calibration */
new_low_prio_task = LOW_PRIO_TASK_MAG_CALIBRATION ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
} else if ( ( int ) ( cmd - > param3 ) = = 1 ) {
/* zero-altitude pressure calibration */
//new_low_prio_task = LOW_PRIO_TASK_ALTITUDE_CALIBRATION;
} else if ( ( int ) ( cmd - > param4 ) = = 1 ) {
/* RC calibration */
new_low_prio_task = LOW_PRIO_TASK_RC_CALIBRATION ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
} else if ( ( int ) ( cmd - > param5 ) = = 1 ) {
/* accelerometer calibration */
new_low_prio_task = LOW_PRIO_TASK_ACCEL_CALIBRATION ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
} else if ( ( int ) ( cmd - > param6 ) = = 1 ) {
/* airspeed calibration */
new_low_prio_task = LOW_PRIO_TASK_AIRSPEED_CALIBRATION ;
2013-07-28 23:12:16 +04:00
}
2013-05-17 11:24:02 +02:00
2013-07-31 20:58:27 +04:00
/* check if we have new task and no other task is scheduled */
if ( low_prio_task = = LOW_PRIO_TASK_NONE & & new_low_prio_task ! = LOW_PRIO_TASK_NONE ) {
2013-07-28 23:12:16 +04:00
/* try to go to INIT/PREFLIGHT arming state */
2013-08-15 09:52:22 +02:00
if ( TRANSITION_DENIED ! = arming_state_transition ( status , safety , ARMING_STATE_INIT , armed ) ) {
2013-07-28 23:12:16 +04:00
result = VEHICLE_CMD_RESULT_ACCEPTED ;
2013-07-31 20:58:27 +04:00
low_prio_task = new_low_prio_task ;
2013-05-17 11:24:02 +02:00
} else {
2013-07-28 23:12:16 +04:00
result = VEHICLE_CMD_RESULT_DENIED ;
2013-02-19 12:32:47 -08:00
}
2013-07-28 23:12:16 +04:00
} else {
result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
}
2013-03-11 11:01:49 -07:00
2013-07-31 20:58:27 +04:00
break ;
}
2013-03-11 11:01:49 -07:00
2013-07-31 20:58:27 +04:00
case VEHICLE_CMD_PREFLIGHT_STORAGE : {
low_prio_task_t new_low_prio_task = LOW_PRIO_TASK_NONE ;
2013-02-19 12:32:47 -08:00
2013-07-31 20:58:27 +04:00
if ( ( ( int ) ( cmd - > param1 ) ) = = 0 ) {
2013-08-15 09:52:22 +02:00
new_low_prio_task = LOW_PRIO_TASK_PARAM_LOAD ;
2013-02-19 12:32:47 -08:00
2013-07-31 20:58:27 +04:00
} else if ( ( ( int ) ( cmd - > param1 ) ) = = 1 ) {
2013-08-15 09:52:22 +02:00
new_low_prio_task = LOW_PRIO_TASK_PARAM_SAVE ;
2013-07-28 23:12:16 +04:00
}
2013-02-19 12:32:47 -08:00
2013-07-31 20:58:27 +04:00
/* check if we have new task and no other task is scheduled */
if ( low_prio_task = = LOW_PRIO_TASK_NONE & & new_low_prio_task ! = LOW_PRIO_TASK_NONE ) {
2013-07-28 23:12:16 +04:00
result = VEHICLE_CMD_RESULT_ACCEPTED ;
2013-07-31 20:58:27 +04:00
low_prio_task = new_low_prio_task ;
2013-01-11 07:42:09 +01:00
2013-07-28 23:12:16 +04:00
} else {
result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2012-11-02 15:21:37 +01:00
}
2013-07-28 23:12:16 +04:00
2013-07-31 20:58:27 +04:00
break ;
}
2012-08-20 23:52:13 +02:00
2013-05-17 11:24:02 +02:00
default :
2012-08-04 15:12:36 -07:00
break ;
}
/* supported command handling stop */
2013-07-31 20:58:27 +04:00
if ( result = = VEHICLE_CMD_RESULT_ACCEPTED ) {
tune_positive ( ) ;
2013-03-25 14:53:54 -07:00
2013-07-31 20:58:27 +04:00
} else {
2013-03-25 14:53:54 -07:00
tune_negative ( ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( result = = VEHICLE_CMD_RESULT_DENIED ) {
mavlink_log_critical ( mavlink_fd , " [cmd] command denied: %u " , cmd - > command ) ;
2013-03-25 14:53:54 -07:00
2013-07-31 20:58:27 +04:00
} else if ( result = = VEHICLE_CMD_RESULT_FAILED ) {
mavlink_log_critical ( mavlink_fd , " [cmd] command failed: %u " , cmd - > command ) ;
} else if ( result = = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ) {
mavlink_log_critical ( mavlink_fd , " [cmd] command temporarily rejected: %u " , cmd - > command ) ;
} else if ( result = = VEHICLE_CMD_RESULT_UNSUPPORTED ) {
mavlink_log_critical ( mavlink_fd , " [cmd] command unsupported: %u " , cmd - > command ) ;
}
2012-11-02 15:21:37 +01:00
}
2012-08-04 15:12:36 -07:00
/* send any requested ACKs */
if ( cmd - > confirmation > 0 ) {
/* send acknowledge command */
2012-08-24 00:01:23 +02:00
// XXX TODO
2012-08-04 15:12:36 -07:00
}
}
2012-08-20 23:52:13 +02:00
int commander_thread_main ( int argc , char * argv [ ] )
2012-08-04 15:12:36 -07:00
{
/* not yet initialized */
commander_initialized = false ;
2013-01-19 14:46:26 +01:00
bool home_position_set = false ;
2012-08-04 15:12:36 -07:00
2013-06-25 13:15:38 +02:00
bool battery_tune_played = false ;
bool arm_tune_played = false ;
2012-09-21 12:55:41 +02:00
/* set parameters */
failsafe_lowlevel_timeout_ms = 0 ;
param_get ( param_find ( " SYS_FAILSAVE_LL " ) , & failsafe_lowlevel_timeout_ms ) ;
2012-12-31 12:31:31 -08:00
param_t _param_sys_type = param_find ( " MAV_TYPE " ) ;
2013-02-17 16:06:33 +01:00
param_t _param_system_id = param_find ( " MAV_SYS_ID " ) ;
param_t _param_component_id = param_find ( " MAV_COMP_ID " ) ;
2012-12-13 10:23:02 +01:00
2012-08-04 15:12:36 -07:00
/* welcome user */
2013-02-16 13:40:09 -08:00
warnx ( " [commander] starting " ) ;
2012-08-04 15:12:36 -07:00
2013-07-16 09:24:21 +02:00
/* pthread for slow low prio thread */
2013-03-25 14:53:54 -07:00
pthread_t commander_low_prio_thread ;
2012-08-04 15:12:36 -07:00
/* initialize */
if ( led_init ( ) ! = 0 ) {
2013-02-16 13:40:09 -08:00
warnx ( " ERROR: Failed to initialize leds " ) ;
2012-08-04 15:12:36 -07:00
}
2013-06-25 16:30:35 +02:00
if ( buzzer_init ( ) ! = OK ) {
2013-02-16 13:40:09 -08:00
warnx ( " ERROR: Failed to initialize buzzer " ) ;
2012-08-04 15:12:36 -07:00
}
mavlink_fd = open ( MAVLINK_LOG_DEVICE , 0 ) ;
if ( mavlink_fd < 0 ) {
2013-02-16 13:40:09 -08:00
warnx ( " ERROR: Failed to open MAVLink log stream, start mavlink app first. " ) ;
2012-08-04 15:12:36 -07:00
}
2013-07-28 23:12:16 +04:00
2013-06-14 13:53:26 +02:00
/* Main state machine */
2013-07-28 23:12:16 +04:00
struct vehicle_status_s status ;
2013-06-14 13:53:26 +02:00
orb_advert_t status_pub ;
2012-08-13 18:53:37 +02:00
/* make sure we are in preflight state */
2013-07-28 23:12:16 +04:00
memset ( & status , 0 , sizeof ( status ) ) ;
2013-03-11 10:39:57 -07:00
2013-07-15 22:15:15 +02:00
/* armed topic */
struct actuator_armed_s armed ;
orb_advert_t armed_pub ;
/* Initialize armed with all false */
memset ( & armed , 0 , sizeof ( armed ) ) ;
2013-06-14 13:53:26 +02:00
/* flags for control apps */
struct vehicle_control_mode_s control_mode ;
orb_advert_t control_mode_pub ;
/* Initialize all flags to false */
memset ( & control_mode , 0 , sizeof ( control_mode ) ) ;
2013-03-11 10:39:57 -07:00
2013-07-28 23:12:16 +04:00
status . main_state = MAIN_STATE_MANUAL ;
status . navigation_state = NAVIGATION_STATE_STANDBY ;
status . arming_state = ARMING_STATE_INIT ;
status . hil_state = HIL_STATE_OFF ;
2013-02-16 13:40:09 -08:00
2012-10-02 13:02:57 +02:00
/* neither manual nor offboard control commands have been received */
2013-07-28 23:12:16 +04:00
status . offboard_control_signal_found_once = false ;
status . rc_signal_found_once = false ;
2013-02-16 13:40:09 -08:00
2012-10-02 13:02:57 +02:00
/* mark all signals lost as long as they haven't been found */
2013-07-28 23:12:16 +04:00
status . rc_signal_lost = true ;
status . offboard_control_signal_lost = true ;
2013-02-16 13:40:09 -08:00
2012-12-13 10:23:02 +01:00
/* allow manual override initially */
2013-07-16 18:55:32 +02:00
control_mode . flag_external_manual_override_ok = true ;
2013-02-16 13:40:09 -08:00
2013-01-08 21:19:23 +01:00
/* set battery warning flag */
2013-07-28 23:12:16 +04:00
status . battery_warning = VEHICLE_BATTERY_WARNING_NONE ;
2013-08-15 17:27:29 +02:00
status . condition_battery_voltage_valid = false ;
2013-07-28 23:12:16 +04:00
2013-02-17 23:07:07 -08:00
// XXX for now just set sensors as initialized
2013-07-28 23:12:16 +04:00
status . condition_system_sensors_initialized = true ;
2013-02-17 23:07:07 -08:00
2013-06-15 19:41:54 +02:00
// XXX just disable offboard control for now
control_mode . flag_control_offboard_enabled = false ;
2012-08-04 15:12:36 -07:00
/* advertise to ORB */
2013-07-28 23:12:16 +04:00
status_pub = orb_advertise ( ORB_ID ( vehicle_status ) , & status ) ;
2012-08-16 15:49:56 +02:00
/* publish current state machine */
2013-07-28 23:12:16 +04:00
2013-07-31 20:58:27 +04:00
/* publish initial state */
2013-07-28 23:12:16 +04:00
status . counter + + ;
status . timestamp = hrt_absolute_time ( ) ;
orb_publish ( ORB_ID ( vehicle_status ) , status_pub , & status ) ;
2013-06-25 16:30:35 +02:00
2013-07-15 22:15:15 +02:00
armed_pub = orb_advertise ( ORB_ID ( actuator_armed ) , & armed ) ;
2013-06-25 13:15:38 +02:00
2013-07-28 23:12:16 +04:00
control_mode_pub = orb_advertise ( ORB_ID ( vehicle_control_mode ) , & control_mode ) ;
2013-06-15 19:41:54 +02:00
2013-01-19 14:46:26 +01:00
/* home position */
orb_advert_t home_pub = - 1 ;
struct home_position_s home ;
memset ( & home , 0 , sizeof ( home ) ) ;
2013-06-14 13:53:26 +02:00
if ( status_pub < 0 ) {
2013-02-18 16:45:59 +01:00
warnx ( " ERROR: orb_advertise for topic vehicle_status failed (uorb app running?). \n " ) ;
warnx ( " exiting. " ) ;
2012-08-11 19:45:32 +02:00
exit ( ERROR ) ;
2012-08-04 15:12:36 -07:00
}
2013-07-31 20:58:27 +04:00
mavlink_log_info ( mavlink_fd , " [cmd] started " ) ;
2012-08-04 15:12:36 -07:00
2013-03-25 14:53:54 -07:00
pthread_attr_t commander_low_prio_attr ;
pthread_attr_init ( & commander_low_prio_attr ) ;
pthread_attr_setstacksize ( & commander_low_prio_attr , 2048 ) ;
struct sched_param param ;
/* low priority */
param . sched_priority = SCHED_PRIORITY_DEFAULT - 50 ;
( void ) pthread_attr_setschedparam ( & commander_low_prio_attr , & param ) ;
pthread_create ( & commander_low_prio_thread , & commander_low_prio_attr , commander_low_prio_loop , NULL ) ;
2012-08-04 15:12:36 -07:00
/* Start monitoring loop */
2013-07-16 18:55:32 +02:00
unsigned counter = 0 ;
unsigned low_voltage_counter = 0 ;
unsigned critical_voltage_counter = 0 ;
unsigned stick_off_counter = 0 ;
unsigned stick_on_counter = 0 ;
2012-08-04 15:12:36 -07:00
2013-07-16 10:05:51 +02:00
/* To remember when last notification was sent */
2013-07-31 20:58:27 +04:00
uint64_t last_print_control_time = 0 ;
2013-03-25 14:53:54 -07:00
2013-07-31 20:58:27 +04:00
enum VEHICLE_BATTERY_WARNING battery_warning_previous = VEHICLE_BATTERY_WARNING_NONE ;
bool armed_previous = false ;
2013-07-16 10:05:51 +02:00
2013-08-15 17:27:29 +02:00
bool low_battery_voltage_actions_done = false ;
bool critical_battery_voltage_actions_done = false ;
2013-07-16 18:55:32 +02:00
2013-07-16 10:05:51 +02:00
uint64_t last_idle_time = 0 ;
uint64_t start_time = 0 ;
2013-07-31 20:58:27 +04:00
bool status_changed = true ;
2013-07-16 10:05:51 +02:00
bool param_init_forced = true ;
2013-07-31 20:58:27 +04:00
bool updated = false ;
2013-07-16 10:05:51 +02:00
2013-07-15 22:15:15 +02:00
/* Subscribe to safety topic */
int safety_sub = orb_subscribe ( ORB_ID ( safety ) ) ;
struct safety_s safety ;
memset ( & safety , 0 , sizeof ( safety ) ) ;
2013-08-15 09:52:22 +02:00
safety . safety_switch_available = false ;
safety . safety_off = false ;
2013-07-15 22:15:15 +02:00
2012-09-21 12:55:41 +02:00
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe ( ORB_ID ( manual_control_setpoint ) ) ;
struct manual_control_setpoint_s sp_man ;
memset ( & sp_man , 0 , sizeof ( sp_man ) ) ;
/* Subscribe to offboard control data */
int sp_offboard_sub = orb_subscribe ( ORB_ID ( offboard_control_setpoint ) ) ;
struct offboard_control_setpoint_s sp_offboard ;
memset ( & sp_offboard , 0 , sizeof ( sp_offboard ) ) ;
2012-08-04 15:12:36 -07:00
2013-02-16 13:40:09 -08:00
/* Subscribe to global position */
2012-12-13 10:23:02 +01:00
int global_position_sub = orb_subscribe ( ORB_ID ( vehicle_global_position ) ) ;
struct vehicle_global_position_s global_position ;
memset ( & global_position , 0 , sizeof ( global_position ) ) ;
2013-02-16 13:40:09 -08:00
/* Subscribe to local position data */
2012-12-13 10:23:02 +01:00
int local_position_sub = orb_subscribe ( ORB_ID ( vehicle_local_position ) ) ;
struct vehicle_local_position_s local_position ;
memset ( & local_position , 0 , sizeof ( local_position ) ) ;
2012-08-04 15:12:36 -07:00
2013-07-28 23:12:16 +04:00
/*
2013-01-19 14:46:26 +01:00
* The home position is set based on GPS only , to prevent a dependency between
* position estimator and commander . RAW GPS is more than good enough for a
* non - flying vehicle .
*/
2013-02-16 13:40:09 -08:00
/* Subscribe to GPS topic */
2013-01-19 14:46:26 +01:00
int gps_sub = orb_subscribe ( ORB_ID ( vehicle_gps_position ) ) ;
struct vehicle_gps_position_s gps_position ;
memset ( & gps_position , 0 , sizeof ( gps_position ) ) ;
2013-02-16 13:40:09 -08:00
/* Subscribe to sensor topic */
2012-08-04 15:12:36 -07:00
int sensor_sub = orb_subscribe ( ORB_ID ( sensor_combined ) ) ;
2012-08-05 22:51:31 +02:00
struct sensor_combined_s sensors ;
memset ( & sensors , 0 , sizeof ( sensors ) ) ;
2012-08-04 15:12:36 -07:00
2013-07-16 10:05:51 +02:00
/* Subscribe to differential pressure topic */
2013-04-19 18:28:06 +02:00
int diff_pres_sub = orb_subscribe ( ORB_ID ( differential_pressure ) ) ;
struct differential_pressure_s diff_pres ;
memset ( & diff_pres , 0 , sizeof ( diff_pres ) ) ;
uint64_t last_diff_pres_time = 0 ;
2013-02-25 15:48:16 +01:00
2012-10-15 08:52:41 +02:00
/* Subscribe to command topic */
int cmd_sub = orb_subscribe ( ORB_ID ( vehicle_command ) ) ;
struct vehicle_command_s cmd ;
memset ( & cmd , 0 , sizeof ( cmd ) ) ;
2012-12-13 10:23:02 +01:00
/* Subscribe to parameters changed topic */
int param_changed_sub = orb_subscribe ( ORB_ID ( parameter_update ) ) ;
struct parameter_update_s param_changed ;
memset ( & param_changed , 0 , sizeof ( param_changed ) ) ;
2013-07-16 10:05:51 +02:00
/* Subscribe to battery topic */
2013-01-01 13:30:24 +01:00
int battery_sub = orb_subscribe ( ORB_ID ( battery_status ) ) ;
struct battery_status_s battery ;
memset ( & battery , 0 , sizeof ( battery ) ) ;
2013-01-06 11:25:17 +01:00
battery . voltage_v = 0.0f ;
2013-01-01 13:30:24 +01:00
2013-07-16 09:24:21 +02:00
/* Subscribe to subsystem info topic */
int subsys_sub = orb_subscribe ( ORB_ID ( subsystem_info ) ) ;
struct subsystem_info_s info ;
memset ( & info , 0 , sizeof ( info ) ) ;
2012-08-04 15:12:36 -07:00
/* now initialized */
commander_initialized = true ;
2013-02-18 16:45:59 +01:00
thread_running = true ;
2012-08-04 15:12:36 -07:00
2013-07-16 10:05:51 +02:00
start_time = hrt_absolute_time ( ) ;
2012-12-23 17:20:53 -08:00
2012-08-24 00:01:23 +02:00
while ( ! thread_should_exit ) {
2013-07-31 20:58:27 +04:00
hrt_abstime t = hrt_absolute_time ( ) ;
2012-08-04 15:12:36 -07:00
2013-08-16 18:05:59 +02:00
status_changed = false ;
2013-06-09 14:09:09 +02:00
/* update parameters */
2013-07-31 20:58:27 +04:00
orb_check ( param_changed_sub , & updated ) ;
2013-06-09 14:09:09 +02:00
2013-07-31 20:58:27 +04:00
if ( updated | | param_init_forced ) {
2013-06-09 14:09:09 +02:00
param_init_forced = false ;
/* parameters changed */
orb_copy ( ORB_ID ( parameter_update ) , param_changed_sub , & param_changed ) ;
/* update parameters */
2013-07-15 22:15:15 +02:00
if ( ! armed . armed ) {
2013-07-28 23:12:16 +04:00
if ( param_get ( _param_sys_type , & ( status . system_type ) ) ! = OK ) {
2013-07-16 10:05:51 +02:00
warnx ( " failed getting new system type " ) ;
2013-06-09 14:09:09 +02:00
}
/* disable manual override for all systems that rely on electronic stabilization */
2013-07-28 23:12:16 +04:00
if ( status . system_type = = VEHICLE_TYPE_COAXIAL | |
status . system_type = = VEHICLE_TYPE_HELICOPTER | |
status . system_type = = VEHICLE_TYPE_TRICOPTER | |
status . system_type = = VEHICLE_TYPE_QUADROTOR | |
status . system_type = = VEHICLE_TYPE_HEXAROTOR | |
status . system_type = = VEHICLE_TYPE_OCTOROTOR ) {
2013-07-16 18:55:32 +02:00
control_mode . flag_external_manual_override_ok = false ;
2013-07-28 23:12:16 +04:00
status . is_rotary_wing = true ;
2013-06-09 14:09:09 +02:00
} else {
2013-07-16 18:55:32 +02:00
control_mode . flag_external_manual_override_ok = true ;
2013-07-28 23:12:16 +04:00
status . is_rotary_wing = false ;
2013-06-09 14:09:09 +02:00
}
/* check and update system / component ID */
2013-07-28 23:12:16 +04:00
param_get ( _param_system_id , & ( status . system_id ) ) ;
param_get ( _param_component_id , & ( status . component_id ) ) ;
2013-07-31 20:58:27 +04:00
status_changed = true ;
2013-06-09 14:09:09 +02:00
}
}
2013-07-31 20:58:27 +04:00
orb_check ( sp_man_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-09-26 21:30:03 +02:00
orb_copy ( ORB_ID ( manual_control_setpoint ) , sp_man_sub , & sp_man ) ;
}
2013-07-31 20:58:27 +04:00
orb_check ( sp_offboard_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-09-26 21:30:03 +02:00
orb_copy ( ORB_ID ( offboard_control_setpoint ) , sp_offboard_sub , & sp_offboard ) ;
}
2012-12-19 11:34:51 +01:00
2013-07-31 20:58:27 +04:00
orb_check ( sensor_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-12-19 11:34:51 +01:00
orb_copy ( ORB_ID ( sensor_combined ) , sensor_sub , & sensors ) ;
}
2012-08-04 15:12:36 -07:00
2013-07-31 20:58:27 +04:00
orb_check ( diff_pres_sub , & updated ) ;
2013-02-25 15:48:16 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2013-04-19 18:28:06 +02:00
orb_copy ( ORB_ID ( differential_pressure ) , diff_pres_sub , & diff_pres ) ;
last_diff_pres_time = diff_pres . timestamp ;
2013-02-25 15:48:16 +01:00
}
2013-07-31 20:58:27 +04:00
orb_check ( cmd_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-10-15 08:52:41 +02:00
/* got command */
orb_copy ( ORB_ID ( vehicle_command ) , cmd_sub , & cmd ) ;
/* handle it */
2013-08-15 09:52:22 +02:00
handle_command ( & status , & safety , & control_mode , & cmd , & armed ) ;
2012-10-15 08:52:41 +02:00
}
2012-12-13 10:23:02 +01:00
2013-06-25 13:15:38 +02:00
/* update safety topic */
2013-07-31 20:58:27 +04:00
orb_check ( safety_sub , & updated ) ;
2013-06-25 13:15:38 +02:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2013-07-15 22:15:15 +02:00
orb_copy ( ORB_ID ( safety ) , safety_sub , & safety ) ;
2013-06-25 13:15:38 +02:00
}
2012-12-13 10:23:02 +01:00
/* update global position estimate */
2013-07-31 20:58:27 +04:00
orb_check ( global_position_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-12-13 10:23:02 +01:00
/* position changed */
orb_copy ( ORB_ID ( vehicle_global_position ) , global_position_sub , & global_position ) ;
}
/* update local position estimate */
2013-07-31 20:58:27 +04:00
orb_check ( local_position_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2012-12-13 10:23:02 +01:00
/* position changed */
orb_copy ( ORB_ID ( vehicle_local_position ) , local_position_sub , & local_position ) ;
}
2013-03-11 10:39:57 -07:00
/* set the condition to valid if there has recently been a local position estimate */
2013-07-31 20:58:27 +04:00
if ( t - local_position . timestamp < LOCAL_POSITION_TIMEOUT ) {
if ( ! status . condition_local_position_valid ) {
status . condition_local_position_valid = true ;
status_changed = true ;
}
2013-07-28 23:12:16 +04:00
2013-03-11 10:39:57 -07:00
} else {
2013-07-31 20:58:27 +04:00
if ( status . condition_local_position_valid ) {
status . condition_local_position_valid = false ;
status_changed = true ;
}
2013-03-11 10:39:57 -07:00
}
2013-01-12 00:38:49 +01:00
/* update battery status */
2013-07-31 20:58:27 +04:00
orb_check ( battery_sub , & updated ) ;
2013-07-28 23:12:16 +04:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2013-01-01 13:30:24 +01:00
orb_copy ( ORB_ID ( battery_status ) , battery_sub , & battery ) ;
2013-07-16 18:55:32 +02:00
2013-08-15 17:27:29 +02:00
/* only consider battery voltage if system has been running 2s and battery voltage is not 0 */
if ( ( t - start_time ) > 2000000 & & battery . voltage_v > 0.001f ) {
status . battery_voltage = battery . voltage_v ;
status . condition_battery_voltage_valid = true ;
status . battery_remaining = battery_remaining_estimate_voltage ( status . battery_voltage ) ;
}
2012-09-05 18:05:11 +02:00
}
2012-08-04 15:12:36 -07:00
2013-07-16 09:24:21 +02:00
/* update subsystem */
2013-07-31 20:58:27 +04:00
orb_check ( subsys_sub , & updated ) ;
2013-07-28 23:12:16 +04:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2013-07-16 09:24:21 +02:00
orb_copy ( ORB_ID ( subsystem_info ) , subsys_sub , & info ) ;
2013-07-31 20:58:27 +04:00
warnx ( " subsystem changed: %d \n " , ( int ) info . subsystem_type ) ;
2013-07-16 09:24:21 +02:00
/* mark / unmark as present */
if ( info . present ) {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_present | = info . subsystem_type ;
2013-07-16 09:24:21 +02:00
} else {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_present & = ~ info . subsystem_type ;
2013-07-16 09:24:21 +02:00
}
/* mark / unmark as enabled */
if ( info . enabled ) {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_enabled | = info . subsystem_type ;
2013-07-16 09:24:21 +02:00
} else {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_enabled & = ~ info . subsystem_type ;
2013-07-16 09:24:21 +02:00
}
/* mark / unmark as ok */
if ( info . ok ) {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_health | = info . subsystem_type ;
2013-07-16 09:24:21 +02:00
} else {
2013-07-28 23:12:16 +04:00
status . onboard_control_sensors_health & = ~ info . subsystem_type ;
2013-07-16 09:24:21 +02:00
}
2012-08-04 15:12:36 -07:00
2013-07-31 20:58:27 +04:00
status_changed = true ;
2013-02-16 13:40:09 -08:00
}
2012-08-04 15:12:36 -07:00
2013-02-16 13:40:09 -08:00
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
/* compute system load */
uint64_t interval_runtime = system_load . tasks [ 0 ] . total_runtime - last_idle_time ;
2012-08-04 15:12:36 -07:00
2013-02-16 13:40:09 -08:00
if ( last_idle_time > 0 )
2013-08-16 10:17:57 +02:00
status . load = 1.0f - ( ( float ) interval_runtime / 1e6 f ) ; //system load is time spent in non-idle
2012-08-04 15:12:36 -07:00
2013-02-16 13:40:09 -08:00
last_idle_time = system_load . tasks [ 0 ] . total_runtime ;
2013-08-17 15:47:42 +02:00
/* check if board is connected via USB */
struct stat statbuf ;
//on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
2012-08-04 15:12:36 -07:00
}
2013-08-17 15:47:42 +02:00
// XXX remove later
//warnx("bat remaining: %2.2f", status.battery_remaining);
2013-08-16 18:05:59 +02:00
2012-09-05 18:05:11 +02:00
/* if battery voltage is getting lower, warn using buzzer, etc. */
2013-08-16 18:05:59 +02:00
if ( status . condition_battery_voltage_valid & & status . battery_remaining < 0.25f & & ! low_battery_voltage_actions_done ) {
2013-07-31 20:58:27 +04:00
//TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
2012-09-05 18:05:11 +02:00
if ( low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT ) {
low_battery_voltage_actions_done = true ;
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] WARNING: LOW BATTERY " ) ;
2013-07-28 23:12:16 +04:00
status . battery_warning = VEHICLE_BATTERY_WARNING_WARNING ;
2013-07-31 20:58:27 +04:00
status_changed = true ;
2013-08-16 18:05:59 +02:00
battery_tune_played = false ;
2012-09-05 18:05:11 +02:00
}
low_voltage_counter + + ;
2013-07-31 20:58:27 +04:00
} else if ( status . condition_battery_voltage_valid & & status . battery_remaining < 0.1f & & ! critical_battery_voltage_actions_done & & low_battery_voltage_actions_done ) {
/* critical battery voltage, this is rather an emergency, change state machine */
2012-09-05 18:05:11 +02:00
if ( critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT ) {
critical_battery_voltage_actions_done = true ;
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] EMERGENCY: CRITICAL BATTERY " ) ;
2013-07-28 23:12:16 +04:00
status . battery_warning = VEHICLE_BATTERY_WARNING_ALERT ;
2013-08-16 18:05:59 +02:00
battery_tune_played = false ;
2013-08-16 09:27:05 +02:00
if ( armed . armed ) {
// XXX not sure what should happen when voltage is low in flight
//arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
} else {
2013-08-16 18:05:59 +02:00
// XXX should we still allow to arm with critical battery?
//arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
2013-08-16 09:27:05 +02:00
}
2013-07-31 20:58:27 +04:00
status_changed = true ;
2012-09-05 18:05:11 +02:00
}
critical_voltage_counter + + ;
} else {
low_voltage_counter = 0 ;
critical_voltage_counter = 0 ;
}
/* End battery voltage check */
2013-02-18 16:35:34 -08:00
/* If in INIT state, try to proceed to STANDBY state */
2013-07-31 20:58:27 +04:00
if ( status . arming_state = = ARMING_STATE_INIT & & low_prio_task = = LOW_PRIO_TASK_NONE ) {
2013-03-26 10:44:49 -07:00
// XXX check for sensors
2013-08-15 09:52:22 +02:00
arming_state_transition ( & status , & safety , ARMING_STATE_STANDBY , & armed ) ;
2013-07-28 23:12:16 +04:00
2013-02-18 16:35:34 -08:00
} else {
// XXX: Add emergency stuff if sensors are lost
}
2012-12-19 14:20:40 +01:00
/*
* Check for valid position information .
*
* If the system has a valid position source from an onboard
* position estimator , it is safe to operate it autonomously .
* The flag_vector_flight_mode_ok flag indicates that a minimum
* set of position measurements is available .
*/
/* store current state to reason later about a state change */
2013-02-22 19:46:47 -08:00
// bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
2013-07-28 23:12:16 +04:00
bool global_pos_valid = status . condition_global_position_valid ;
bool local_pos_valid = status . condition_local_position_valid ;
bool airspeed_valid = status . condition_airspeed_valid ;
2013-03-11 11:01:49 -07:00
2012-12-13 10:23:02 +01:00
/* check for global or local position updates, set a timeout of 2s */
2013-07-31 20:58:27 +04:00
if ( t - global_position . timestamp < 2000000 & & t > 2000000 & & global_position . valid ) {
2013-07-28 23:12:16 +04:00
status . condition_global_position_valid = true ;
2013-01-11 07:42:09 +01:00
2012-12-19 14:20:40 +01:00
} else {
2013-07-28 23:12:16 +04:00
status . condition_global_position_valid = false ;
2012-12-13 10:23:02 +01:00
}
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( t - local_position . timestamp < 2000000 & & t > 2000000 & & local_position . valid ) {
2013-07-28 23:12:16 +04:00
status . condition_local_position_valid = true ;
2013-01-11 07:42:09 +01:00
2012-12-19 14:20:40 +01:00
} else {
2013-07-28 23:12:16 +04:00
status . condition_local_position_valid = false ;
2012-12-19 14:20:40 +01:00
}
2013-02-25 15:48:16 +01:00
/* Check for valid airspeed/differential pressure measurements */
2013-07-31 20:58:27 +04:00
if ( t - last_diff_pres_time < 2000000 & & t > 2000000 ) {
2013-07-28 23:12:16 +04:00
status . condition_airspeed_valid = true ;
2013-02-25 15:48:16 +01:00
} else {
2013-07-28 23:12:16 +04:00
status . condition_airspeed_valid = false ;
2013-02-25 15:48:16 +01:00
}
2013-07-31 20:58:27 +04:00
orb_check ( gps_sub , & updated ) ;
2012-12-13 10:23:02 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2013-01-19 14:46:26 +01:00
orb_copy ( ORB_ID ( vehicle_gps_position ) , gps_sub , & gps_position ) ;
2012-08-04 15:12:36 -07:00
2013-01-19 14:46:26 +01:00
/* check for first, long-term and valid GPS lock -> set home position */
2013-02-06 12:41:05 -08:00
float hdop_m = gps_position . eph_m ;
float vdop_m = gps_position . epv_m ;
2013-01-19 14:46:26 +01:00
2013-07-31 20:58:27 +04:00
/* check if GPS fix is ok */
2013-02-06 13:50:32 -08:00
float hdop_threshold_m = 4.0f ;
float vdop_threshold_m = 8.0f ;
2013-01-19 14:46:26 +01:00
/*
* If horizontal dilution of precision ( hdop / eph )
* and vertical diluation of precision ( vdop / epv )
* are below a certain threshold ( e . g . 4 m ) , AND
* home position is not yet set AND the last GPS
* GPS measurement is not older than two seconds AND
* the system is currently not armed , set home
* position to the current position .
*/
2013-02-06 13:50:32 -08:00
2013-07-31 20:58:27 +04:00
if ( ! home_position_set & & gps_position . fix_type = = GPS_FIX_TYPE_3D & &
( hdop_m < hdop_threshold_m ) & & ( vdop_m < vdop_threshold_m ) & & // XXX note that vdop is 0 for mtk
( t - gps_position . timestamp_position < 2000000 )
2013-07-28 23:12:16 +04:00
& & ! armed . armed ) {
2013-01-19 14:46:26 +01:00
/* copy position data to uORB home message, store it locally as well */
2013-07-31 20:58:27 +04:00
// TODO use global position estimate
2013-01-19 14:46:26 +01:00
home . lat = gps_position . lat ;
home . lon = gps_position . lon ;
home . alt = gps_position . alt ;
2013-02-06 12:41:05 -08:00
home . eph_m = gps_position . eph_m ;
home . epv_m = gps_position . epv_m ;
2013-01-19 14:46:26 +01:00
2013-02-06 12:41:05 -08:00
home . s_variance_m_s = gps_position . s_variance_m_s ;
home . p_variance_m = gps_position . p_variance_m ;
2013-01-19 14:46:26 +01:00
2013-07-31 20:58:27 +04:00
double home_lat_d = home . lat * 1e-7 ;
double home_lon_d = home . lon * 1e-7 ;
warnx ( " home: lat = %.7f, lon = %.7f " , home_lat_d , home_lon_d ) ;
mavlink_log_info ( mavlink_fd , " [cmd] home: %.7f, %.7f " , home_lat_d , home_lon_d ) ;
2013-01-19 14:46:26 +01:00
/* announce new home position */
if ( home_pub > 0 ) {
orb_publish ( ORB_ID ( home_position ) , home_pub , & home ) ;
2013-07-28 23:12:16 +04:00
2013-01-19 14:46:26 +01:00
} else {
home_pub = orb_advertise ( ORB_ID ( home_position ) , & home ) ;
}
2012-08-04 15:12:36 -07:00
2013-01-19 17:03:35 +01:00
/* mark home position as set */
home_position_set = true ;
2013-03-25 14:53:54 -07:00
tune_positive ( ) ;
2013-01-19 14:46:26 +01:00
}
}
2012-08-04 15:12:36 -07:00
2012-09-21 12:55:41 +02:00
/* ignore RC signals if in offboard control mode */
2013-07-28 23:12:16 +04:00
if ( ! status . offboard_control_signal_found_once & & sp_man . timestamp ! = 0 ) {
2013-07-31 20:58:27 +04:00
/* start RC input check */
if ( ( t - sp_man . timestamp ) < 100000 ) {
2013-07-28 23:12:16 +04:00
/* handle the case where RC signal was regained */
if ( ! status . rc_signal_found_once ) {
status . rc_signal_found_once = true ;
mavlink_log_critical ( mavlink_fd , " [cmd] detected RC signal first time " ) ;
2013-07-31 20:58:27 +04:00
status_changed = true ;
2013-02-20 10:38:06 -08:00
} else {
2013-07-28 23:12:16 +04:00
if ( status . rc_signal_lost ) {
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] RC signal regained " ) ;
status_changed = true ;
2013-07-28 23:12:16 +04:00
}
2013-02-20 10:38:06 -08:00
}
2012-12-27 18:27:08 +01:00
2013-07-28 23:12:16 +04:00
status . rc_signal_cutting_off = false ;
status . rc_signal_lost = false ;
status . rc_signal_lost_interval = 0 ;
2012-12-29 11:00:15 +01:00
2013-07-28 23:12:16 +04:00
transition_result_t res ; // store all transitions results here
2012-12-27 18:27:08 +01:00
2013-07-28 23:12:16 +04:00
/* arm/disarm by RC */
res = TRANSITION_NOT_CHANGED ;
2012-12-27 18:27:08 +01:00
2013-07-28 23:12:16 +04:00
/* check if left stick is in lower left position and we are in MANUAL or AUTO mode -> disarm
* do it only for rotary wings */
if ( status . is_rotary_wing & &
( status . arming_state = = ARMING_STATE_ARMED | | status . arming_state = = ARMING_STATE_ARMED_ERROR ) & &
( status . main_state = = MAIN_STATE_MANUAL | | status . navigation_state = = NAVIGATION_STATE_AUTO_READY ) ) {
if ( sp_man . yaw < - STICK_ON_OFF_LIMIT & & sp_man . throttle < STICK_THRUST_RANGE * 0.1f ) {
if ( stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT ) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = ( status . arming_state = = ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR ) ;
2013-08-15 09:52:22 +02:00
res = arming_state_transition ( & status , & safety , new_arming_state , & armed ) ;
2013-07-31 20:58:27 +04:00
stick_off_counter = 0 ;
2013-02-16 13:40:09 -08:00
2013-07-28 23:12:16 +04:00
} else {
stick_off_counter + + ;
}
2013-07-22 21:48:21 +04:00
2013-07-31 20:58:27 +04:00
stick_on_counter = 0 ;
2013-07-28 23:12:16 +04:00
} else {
stick_off_counter = 0 ;
}
2013-07-22 21:48:21 +04:00
}
2013-07-28 23:12:16 +04:00
/* check if left stick is in lower right position and we're in manual mode -> arm */
if ( status . arming_state = = ARMING_STATE_STANDBY & &
status . main_state = = MAIN_STATE_MANUAL ) {
if ( sp_man . yaw > STICK_ON_OFF_LIMIT & & sp_man . throttle < STICK_THRUST_RANGE * 0.1f ) {
if ( stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT ) {
2013-08-15 09:52:22 +02:00
res = arming_state_transition ( & status , & safety , ARMING_STATE_ARMED , & armed ) ;
2013-07-31 20:58:27 +04:00
stick_on_counter = 0 ;
2013-02-16 13:40:09 -08:00
2013-07-28 23:12:16 +04:00
} else {
stick_on_counter + + ;
}
2013-02-16 13:40:09 -08:00
2013-07-31 20:58:27 +04:00
stick_off_counter = 0 ;
2013-07-28 23:12:16 +04:00
} else {
stick_on_counter = 0 ;
}
}
2013-02-16 13:40:09 -08:00
2013-07-28 23:12:16 +04:00
if ( res = = TRANSITION_CHANGED ) {
if ( status . arming_state = = ARMING_STATE_ARMED ) {
mavlink_log_info ( mavlink_fd , " [cmd] ARMED by RC " ) ;
2013-02-16 13:40:09 -08:00
2013-07-28 23:12:16 +04:00
} else {
mavlink_log_info ( mavlink_fd , " [cmd] DISARMED by RC " ) ;
}
2013-02-20 10:38:06 -08:00
}
2013-07-28 23:12:16 +04:00
/* fill current_status according to mode switches */
check_mode_switches ( & sp_man , & status ) ;
2013-02-16 13:40:09 -08:00
2013-07-28 23:12:16 +04:00
/* evaluate the main state machine */
res = check_main_state_machine ( & status ) ;
2013-07-31 20:58:27 +04:00
if ( res = = TRANSITION_CHANGED ) {
mavlink_log_info ( mavlink_fd , " [cmd] main state: %d " , status . main_state ) ;
tune_positive ( ) ;
2012-08-04 15:12:36 -07:00
2013-07-31 20:58:27 +04:00
} else if ( res = = TRANSITION_DENIED ) {
/* DENIED here indicates bug in the commander */
warnx ( " ERROR: main denied: arm %d main %d mode_sw %d " , status . arming_state , status . main_state , status . mode_switch ) ;
mavlink_log_critical ( mavlink_fd , " [cmd] ERROR: main denied: arm %d main %d mode_sw %d " , status . arming_state , status . main_state , status . mode_switch ) ;
2013-07-28 23:12:16 +04:00
}
2012-08-08 18:47:46 +02:00
} else {
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
/* print error message for first RC glitch and then every 5s */
if ( ! status . rc_signal_cutting_off | | ( t - last_print_control_time ) > PRINT_INTERVAL ) {
// TODO remove debug code
2013-07-28 23:12:16 +04:00
if ( ! status . rc_signal_cutting_off ) {
2013-07-31 20:58:27 +04:00
warnx ( " Reason: not rc_signal_cutting_off \n " ) ;
2013-07-28 23:12:16 +04:00
2013-03-25 14:53:54 -07:00
} else {
2013-07-31 20:58:27 +04:00
warnx ( " last print time: %llu \n " , last_print_control_time ) ;
2013-03-25 14:53:54 -07:00
}
2013-07-31 20:58:27 +04:00
/* only complain if the offboard control is NOT active */
status . rc_signal_cutting_off = true ;
mavlink_log_critical ( mavlink_fd , " [cmd] CRITICAL: NO RC CONTROL " ) ;
last_print_control_time = t ;
2012-09-21 12:55:41 +02:00
}
2013-01-11 07:42:09 +01:00
2012-09-21 12:55:41 +02:00
/* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
2013-07-31 20:58:27 +04:00
status . rc_signal_lost_interval = t - sp_man . timestamp ;
2012-09-21 12:55:41 +02:00
/* if the RC signal is gone for a full second, consider it lost */
2013-07-28 23:12:16 +04:00
if ( status . rc_signal_lost_interval > 1000000 ) {
status . rc_signal_lost = true ;
status . failsave_lowlevel = true ;
2013-07-31 20:58:27 +04:00
status_changed = true ;
2012-09-21 12:55:41 +02:00
}
2012-08-08 18:47:46 +02:00
}
2012-08-04 15:12:36 -07:00
}
2013-07-31 20:58:27 +04:00
/* END mode switch */
2012-08-04 15:12:36 -07:00
/* END RC state check */
2013-07-31 20:58:27 +04:00
// TODO check this
/* state machine update for offboard control */
2013-07-28 23:12:16 +04:00
if ( ! status . rc_signal_found_once & & sp_offboard . timestamp ! = 0 ) {
2013-07-31 20:58:27 +04:00
if ( ( t - sp_offboard . timestamp ) < 5000000 ) { // TODO 5s is too long ?
2012-09-21 12:55:41 +02:00
2013-06-15 19:41:54 +02:00
// /* decide about attitude control flag, enable in att/pos/vel */
// bool attitude_ctrl_enabled = (sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE ||
// sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY ||
// sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION);
2012-09-21 12:55:41 +02:00
2013-06-15 19:41:54 +02:00
// /* decide about rate control flag, enable it always XXX (for now) */
// bool rates_ctrl_enabled = true;
2012-09-21 12:55:41 +02:00
2013-06-15 19:41:54 +02:00
// /* set up control mode */
// if (current_status.flag_control_attitude_enabled != attitude_ctrl_enabled) {
// current_status.flag_control_attitude_enabled = attitude_ctrl_enabled;
// state_changed = true;
// }
2013-01-11 07:42:09 +01:00
2013-06-15 19:41:54 +02:00
// if (current_status.flag_control_rates_enabled != rates_ctrl_enabled) {
// current_status.flag_control_rates_enabled = rates_ctrl_enabled;
// state_changed = true;
// }
2013-01-11 07:42:09 +01:00
2013-06-15 19:41:54 +02:00
// /* handle the case where offboard control signal was regained */
// if (!current_status.offboard_control_signal_found_once) {
// current_status.offboard_control_signal_found_once = true;
// /* enable offboard control, disable manual input */
// current_status.flag_control_manual_enabled = false;
// current_status.flag_control_offboard_enabled = true;
// state_changed = true;
// tune_positive();
// mavlink_log_critical(mavlink_fd, "DETECTED OFFBOARD SIGNAL FIRST");
// } else {
// if (current_status.offboard_control_signal_lost) {
// mavlink_log_critical(mavlink_fd, "RECOVERY OFFBOARD CONTROL");
// state_changed = true;
// tune_positive();
// }
// }
2012-09-21 12:55:41 +02:00
2013-07-28 23:12:16 +04:00
status . offboard_control_signal_weak = false ;
status . offboard_control_signal_lost = false ;
status . offboard_control_signal_lost_interval = 0 ;
2012-09-21 12:55:41 +02:00
2013-03-26 10:44:49 -07:00
// XXX check if this is correct
2012-09-21 12:55:41 +02:00
/* arm / disarm on request */
2013-07-15 22:15:15 +02:00
if ( sp_offboard . armed & & ! armed . armed ) {
2013-08-15 09:52:22 +02:00
arming_state_transition ( & status , & safety , ARMING_STATE_ARMED , & armed ) ;
2013-01-11 07:42:09 +01:00
2013-07-15 22:15:15 +02:00
} else if ( ! sp_offboard . armed & & armed . armed ) {
2013-08-15 09:52:22 +02:00
arming_state_transition ( & status , & safety , ARMING_STATE_STANDBY , & armed ) ;
2012-09-21 12:55:41 +02:00
}
} else {
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
/* print error message for first offboard signal glitch and then every 5s */
if ( ! status . offboard_control_signal_weak | | ( ( t - last_print_control_time ) > PRINT_INTERVAL ) ) {
2013-07-28 23:12:16 +04:00
status . offboard_control_signal_weak = true ;
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] CRITICAL: NO OFFBOARD CONTROL " ) ;
last_print_control_time = t ;
2012-09-21 12:55:41 +02:00
}
2013-01-11 07:42:09 +01:00
2012-09-21 12:55:41 +02:00
/* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
2013-07-31 20:58:27 +04:00
status . offboard_control_signal_lost_interval = t - sp_offboard . timestamp ;
2012-09-21 12:55:41 +02:00
/* if the signal is gone for 0.1 seconds, consider it lost */
2013-07-28 23:12:16 +04:00
if ( status . offboard_control_signal_lost_interval > 100000 ) {
status . offboard_control_signal_lost = true ;
2013-07-31 20:58:27 +04:00
status . failsave_lowlevel_start_time = t ;
2013-03-25 14:53:54 -07:00
tune_positive ( ) ;
2012-09-21 12:55:41 +02:00
/* kill motors after timeout */
2013-07-31 20:58:27 +04:00
if ( t - status . failsave_lowlevel_start_time > failsafe_lowlevel_timeout_ms * 1000 ) {
2013-07-28 23:12:16 +04:00
status . failsave_lowlevel = true ;
2013-07-31 20:58:27 +04:00
status_changed = true ;
2012-09-21 12:55:41 +02:00
}
}
}
}
2013-07-31 20:58:27 +04:00
/* evaluate the navigation state machine */
transition_result_t res = check_navigation_state_machine ( & status , & control_mode ) ;
2012-09-21 12:55:41 +02:00
2013-07-31 20:58:27 +04:00
if ( res = = TRANSITION_DENIED ) {
/* DENIED here indicates bug in the commander */
warnx ( " ERROR: nav denied: arm %d main %d nav %d " , status . arming_state , status . main_state , status . navigation_state ) ;
mavlink_log_critical ( mavlink_fd , " [cmd] ERROR: nav denied: arm %d main %d nav %d " , status . arming_state , status . main_state , status . navigation_state ) ;
}
2013-06-25 13:15:38 +02:00
2013-07-31 20:58:27 +04:00
/* check which state machines for changes, clear "changed" flag */
bool arming_state_changed = check_arming_state_changed ( ) ;
bool main_state_changed = check_main_state_changed ( ) ;
bool navigation_state_changed = check_navigation_state_changed ( ) ;
2013-06-25 13:15:38 +02:00
2013-07-31 20:58:27 +04:00
if ( arming_state_changed | | main_state_changed | | navigation_state_changed ) {
mavlink_log_info ( mavlink_fd , " [cmd] state: arm %d, main %d, nav %d " , status . arming_state , status . main_state , status . navigation_state ) ;
status_changed = true ;
}
2012-08-08 18:47:46 +02:00
2013-07-31 20:58:27 +04:00
/* publish arming state */
if ( arming_state_changed ) {
armed . timestamp = t ;
orb_publish ( ORB_ID ( actuator_armed ) , armed_pub , & armed ) ;
}
2012-08-04 15:12:36 -07:00
2013-07-31 20:58:27 +04:00
/* publish control mode */
if ( navigation_state_changed ) {
/* publish new navigation state */
control_mode . counter + + ;
control_mode . timestamp = t ;
orb_publish ( ORB_ID ( vehicle_control_mode ) , control_mode_pub , & control_mode ) ;
}
2013-03-26 10:44:49 -07:00
2013-07-31 20:58:27 +04:00
/* publish vehicle status at least with 1 Hz */
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 | | status_changed ) {
status . counter + + ;
status . timestamp = t ;
2013-07-28 23:12:16 +04:00
orb_publish ( ORB_ID ( vehicle_status ) , status_pub , & status ) ;
2012-08-16 15:49:56 +02:00
}
2013-07-31 20:58:27 +04:00
/* play arming and battery warning tunes */
2013-08-15 09:52:22 +02:00
if ( ! arm_tune_played & & armed . armed ) {
2013-07-31 20:58:27 +04:00
/* play tune when armed */
2013-06-25 16:30:35 +02:00
if ( tune_arm ( ) = = OK )
2013-06-25 14:45:27 +02:00
arm_tune_played = true ;
2013-06-25 13:15:38 +02:00
2013-07-31 20:58:27 +04:00
} else if ( status . battery_warning = = VEHICLE_BATTERY_WARNING_WARNING ) {
/* play tune on battery warning */
if ( tune_low_bat ( ) = = OK )
2013-06-25 14:45:27 +02:00
battery_tune_played = true ;
2013-07-28 23:12:16 +04:00
2013-08-16 18:05:59 +02:00
} else if ( status . battery_warning = = VEHICLE_BATTERY_WARNING_ALERT ) {
2013-07-31 20:58:27 +04:00
/* play tune on battery critical */
if ( tune_critical_bat ( ) = = OK )
2013-06-25 14:45:27 +02:00
battery_tune_played = true ;
2013-07-28 23:12:16 +04:00
} else if ( battery_tune_played ) {
2013-06-25 16:30:35 +02:00
tune_stop ( ) ;
2013-06-25 13:15:38 +02:00
battery_tune_played = false ;
}
/* reset arm_tune_played when disarmed */
2013-07-28 23:12:16 +04:00
if ( ! ( armed . armed & & ( ! safety . safety_switch_available | | ( safety . safety_off & & safety . safety_switch_available ) ) ) ) {
2013-06-25 13:15:38 +02:00
arm_tune_played = false ;
}
2013-07-31 20:58:27 +04:00
/* store old modes to detect and act on state transitions */
battery_warning_previous = status . battery_warning ;
armed_previous = armed . armed ;
2013-06-25 13:15:38 +02:00
2012-08-04 15:12:36 -07:00
fflush ( stdout ) ;
counter + + ;
2013-08-16 18:05:59 +02:00
toggle_status_leds ( & status , & armed , arming_state_changed | | status_changed ) ;
2012-08-04 15:12:36 -07:00
usleep ( COMMANDER_MONITORING_INTERVAL ) ;
}
/* wait for threads to complete */
2013-03-25 14:53:54 -07:00
pthread_join ( commander_low_prio_thread , NULL ) ;
2012-08-04 15:12:36 -07:00
/* close fds */
led_deinit ( ) ;
buzzer_deinit ( ) ;
2012-09-21 12:55:41 +02:00
close ( sp_man_sub ) ;
close ( sp_offboard_sub ) ;
2013-07-16 10:05:51 +02:00
close ( local_position_sub ) ;
2012-12-13 10:23:02 +01:00
close ( global_position_sub ) ;
2013-07-16 10:05:51 +02:00
close ( gps_sub ) ;
2012-08-24 00:01:23 +02:00
close ( sensor_sub ) ;
2013-07-15 22:15:15 +02:00
close ( safety_sub ) ;
2012-10-15 08:52:41 +02:00
close ( cmd_sub ) ;
2013-07-16 09:24:21 +02:00
close ( subsys_sub ) ;
2013-07-16 10:05:51 +02:00
close ( diff_pres_sub ) ;
close ( param_changed_sub ) ;
close ( battery_sub ) ;
2012-08-24 00:01:23 +02:00
2013-02-16 13:40:09 -08:00
warnx ( " exiting " ) ;
2012-08-24 00:01:23 +02:00
fflush ( stdout ) ;
2012-08-04 15:12:36 -07:00
2012-08-20 23:52:13 +02:00
thread_running = false ;
2012-08-04 15:12:36 -07:00
return 0 ;
}
2013-03-25 14:53:54 -07:00
2013-07-31 20:58:27 +04:00
void
2013-08-16 18:05:59 +02:00
toggle_status_leds ( vehicle_status_s * status , actuator_armed_s * armed , bool changed )
2013-07-31 20:58:27 +04:00
{
2013-08-16 18:05:59 +02:00
# ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
if ( armed - > armed ) {
/* armed, solid */
led_on ( LED_BLUE ) ;
} else if ( armed - > ready_to_arm ) {
/* ready to arm, blink at 1Hz */
if ( leds_counter % 20 = = 0 )
led_toggle ( LED_BLUE ) ;
} else {
/* not ready to arm, blink at 10Hz */
if ( leds_counter % 2 = = 0 )
led_toggle ( LED_BLUE ) ;
}
# endif
if ( changed ) {
warnx ( " changed " ) ;
int i ;
rgbled_pattern_t pattern ;
memset ( & pattern , 0 , sizeof ( pattern ) ) ;
2013-07-31 20:58:27 +04:00
if ( armed - > armed ) {
/* armed, solid */
2013-08-16 18:05:59 +02:00
if ( status - > battery_warning = = VEHICLE_BATTERY_WARNING_WARNING ) {
2013-08-17 15:47:42 +02:00
pattern . color [ 0 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_AMBER : RGBLED_COLOR_AMBER ;
2013-08-16 18:05:59 +02:00
} else if ( status - > battery_warning = = VEHICLE_BATTERY_WARNING_ALERT ) {
2013-08-17 15:47:42 +02:00
pattern . color [ 0 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED ;
2013-08-16 18:05:59 +02:00
} else {
2013-08-17 15:47:42 +02:00
pattern . color [ 0 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_GREEN : RGBLED_COLOR_GREEN ;
2013-08-16 18:05:59 +02:00
}
pattern . duration [ 0 ] = 1000 ;
2013-07-31 20:58:27 +04:00
} else if ( armed - > ready_to_arm ) {
2013-08-16 18:05:59 +02:00
for ( i = 0 ; i < 3 ; i + + ) {
if ( status - > battery_warning = = VEHICLE_BATTERY_WARNING_WARNING ) {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_AMBER : RGBLED_COLOR_AMBER ;
2013-08-16 18:05:59 +02:00
} else if ( status - > battery_warning = = VEHICLE_BATTERY_WARNING_ALERT ) {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED ;
2013-08-16 18:05:59 +02:00
} else {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_GREEN : RGBLED_COLOR_GREEN ;
2013-08-16 18:05:59 +02:00
}
pattern . duration [ i * 2 ] = 200 ;
2013-08-15 10:33:45 +02:00
2013-08-16 18:05:59 +02:00
pattern . color [ i * 2 + 1 ] = RGBLED_COLOR_OFF ;
pattern . duration [ i * 2 + 1 ] = 800 ;
}
if ( status - > condition_global_position_valid ) {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_BLUE : RGBLED_COLOR_BLUE ;
2013-08-16 18:05:59 +02:00
pattern . duration [ i * 2 ] = 1000 ;
pattern . color [ i * 2 + 1 ] = RGBLED_COLOR_OFF ;
pattern . duration [ i * 2 + 1 ] = 800 ;
2013-08-14 10:59:22 +02:00
} else {
2013-08-16 18:05:59 +02:00
for ( i = 3 ; i < 6 ; i + + ) {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_BLUE : RGBLED_COLOR_BLUE ;
2013-08-16 18:05:59 +02:00
pattern . duration [ i * 2 ] = 100 ;
pattern . color [ i * 2 + 1 ] = RGBLED_COLOR_OFF ;
pattern . duration [ i * 2 + 1 ] = 100 ;
}
pattern . color [ 6 * 2 ] = RGBLED_COLOR_OFF ;
pattern . duration [ 6 * 2 ] = 700 ;
2013-07-31 20:58:27 +04:00
}
} else {
2013-08-16 18:05:59 +02:00
for ( i = 0 ; i < 3 ; i + + ) {
2013-08-17 15:47:42 +02:00
pattern . color [ i * 2 ] = ( on_usb_power ) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED ;
2013-08-16 18:05:59 +02:00
pattern . duration [ i * 2 ] = 200 ;
pattern . color [ i * 2 + 1 ] = RGBLED_COLOR_OFF ;
pattern . duration [ i * 2 + 1 ] = 200 ;
}
2013-07-31 20:58:27 +04:00
/* not ready to arm, blink at 10Hz */
}
2013-08-16 18:05:59 +02:00
rgbled_set_pattern ( & pattern ) ;
}
2013-07-31 20:58:27 +04:00
2013-08-16 18:05:59 +02:00
/* give system warnings on error LED, XXX maybe add memory usage warning too */
if ( status - > load > 0.95f ) {
if ( leds_counter % 2 = = 0 )
led_toggle ( LED_AMBER ) ;
} else {
led_off ( LED_AMBER ) ;
2013-07-31 20:58:27 +04:00
}
leds_counter + + ;
}
2013-07-28 23:12:16 +04:00
void
check_mode_switches ( struct manual_control_setpoint_s * sp_man , struct vehicle_status_s * current_status )
{
/* main mode switch */
if ( ! isfinite ( sp_man - > mode_switch ) ) {
warnx ( " mode sw not finite " ) ;
current_status - > mode_switch = MODE_SWITCH_MANUAL ;
} else if ( sp_man - > mode_switch > STICK_ON_OFF_LIMIT ) {
current_status - > mode_switch = MODE_SWITCH_AUTO ;
2013-07-31 20:58:27 +04:00
} else if ( sp_man - > mode_switch < - STICK_ON_OFF_LIMIT ) {
2013-07-28 23:12:16 +04:00
current_status - > mode_switch = MODE_SWITCH_MANUAL ;
2013-07-31 20:58:27 +04:00
} else {
current_status - > mode_switch = MODE_SWITCH_ASSISTED ;
2013-07-28 23:12:16 +04:00
}
/* land switch */
if ( ! isfinite ( sp_man - > return_switch ) ) {
current_status - > return_switch = RETURN_SWITCH_NONE ;
} else if ( sp_man - > return_switch > STICK_ON_OFF_LIMIT ) {
current_status - > return_switch = RETURN_SWITCH_RETURN ;
} else {
current_status - > return_switch = RETURN_SWITCH_NONE ;
}
/* assisted switch */
if ( ! isfinite ( sp_man - > assisted_switch ) ) {
current_status - > assisted_switch = ASSISTED_SWITCH_SEATBELT ;
} else if ( sp_man - > assisted_switch > STICK_ON_OFF_LIMIT ) {
current_status - > assisted_switch = ASSISTED_SWITCH_EASY ;
} else {
current_status - > assisted_switch = ASSISTED_SWITCH_SEATBELT ;
}
/* mission switch */
if ( ! isfinite ( sp_man - > mission_switch ) ) {
current_status - > mission_switch = MISSION_SWITCH_MISSION ;
} else if ( sp_man - > mission_switch > STICK_ON_OFF_LIMIT ) {
current_status - > mission_switch = MISSION_SWITCH_NONE ;
} else {
current_status - > mission_switch = MISSION_SWITCH_MISSION ;
}
}
transition_result_t
check_main_state_machine ( struct vehicle_status_s * current_status )
{
/* evaluate the main state machine */
transition_result_t res = TRANSITION_DENIED ;
switch ( current_status - > mode_switch ) {
case MODE_SWITCH_MANUAL :
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_MANUAL ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
case MODE_SWITCH_ASSISTED :
if ( current_status - > assisted_switch = = ASSISTED_SWITCH_EASY ) {
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_EASY ) ;
2013-07-28 23:12:16 +04:00
if ( res ! = TRANSITION_DENIED )
break ; // changed successfully or already in this state
// else fallback to SEATBELT
2013-07-31 20:58:27 +04:00
print_reject_mode ( " EASY " ) ;
2013-07-28 23:12:16 +04:00
}
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_SEATBELT ) ;
2013-07-28 23:12:16 +04:00
if ( res ! = TRANSITION_DENIED )
break ; // changed successfully or already in this mode
2013-07-31 20:58:27 +04:00
if ( current_status - > assisted_switch ! = ASSISTED_SWITCH_EASY ) // don't print both messages
print_reject_mode ( " SEATBELT " ) ;
2013-07-28 23:12:16 +04:00
// else fallback to MANUAL
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_MANUAL ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
case MODE_SWITCH_AUTO :
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_AUTO ) ;
2013-07-28 23:12:16 +04:00
if ( res ! = TRANSITION_DENIED )
break ; // changed successfully or already in this state
// else fallback to SEATBELT (EASY likely will not work too)
2013-07-31 20:58:27 +04:00
print_reject_mode ( " AUTO " ) ;
res = main_state_transition ( current_status , MAIN_STATE_SEATBELT ) ;
2013-07-28 23:12:16 +04:00
if ( res ! = TRANSITION_DENIED )
break ; // changed successfully or already in this state
// else fallback to MANUAL
2013-07-31 20:58:27 +04:00
res = main_state_transition ( current_status , MAIN_STATE_MANUAL ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
default :
break ;
}
return res ;
}
2013-07-31 20:58:27 +04:00
void
print_reject_mode ( const char * msg )
{
hrt_abstime t = hrt_absolute_time ( ) ;
if ( t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL ) {
last_print_mode_reject_time = t ;
char s [ 80 ] ;
sprintf ( s , " [cmd] WARNING: reject %s " , msg ) ;
mavlink_log_critical ( mavlink_fd , s ) ;
tune_negative ( ) ;
}
}
2013-07-28 23:12:16 +04:00
transition_result_t
check_navigation_state_machine ( struct vehicle_status_s * current_status , struct vehicle_control_mode_s * control_mode )
{
transition_result_t res = TRANSITION_DENIED ;
if ( current_status - > arming_state = = ARMING_STATE_ARMED | | current_status - > arming_state = = ARMING_STATE_ARMED_ERROR ) {
/* ARMED */
switch ( current_status - > main_state ) {
case MAIN_STATE_MANUAL :
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , current_status - > is_rotary_wing ? NAVIGATION_STATE_STABILIZE : NAVIGATION_STATE_DIRECT , control_mode ) ;
2013-07-28 23:12:16 +04:00
break ;
case MAIN_STATE_SEATBELT :
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_ALTHOLD , control_mode ) ;
2013-07-28 23:12:16 +04:00
break ;
case MAIN_STATE_EASY :
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_VECTOR , control_mode ) ;
2013-07-28 23:12:16 +04:00
break ;
case MAIN_STATE_AUTO :
if ( current_status - > navigation_state ! = NAVIGATION_STATE_AUTO_TAKEOFF ) {
/* don't act while taking off */
if ( current_status - > condition_landed ) {
/* if landed: transitions only to AUTO_READY are allowed */
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_AUTO_READY , control_mode ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
} else {
/* if not landed: act depending on switches */
if ( current_status - > return_switch = = RETURN_SWITCH_RETURN ) {
/* RTL */
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_AUTO_RTL , control_mode ) ;
2013-07-28 23:12:16 +04:00
} else {
if ( current_status - > mission_switch = = MISSION_SWITCH_MISSION ) {
/* MISSION */
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_AUTO_MISSION , control_mode ) ;
2013-07-28 23:12:16 +04:00
} else {
/* LOITER */
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_AUTO_LOITER , control_mode ) ;
2013-07-28 23:12:16 +04:00
}
}
}
}
break ;
default :
break ;
}
} else {
/* DISARMED */
2013-07-31 20:58:27 +04:00
res = navigation_state_transition ( current_status , NAVIGATION_STATE_STANDBY , control_mode ) ;
2013-07-28 23:12:16 +04:00
}
return res ;
}
2013-03-25 14:53:54 -07:00
2013-03-26 10:44:49 -07:00
void * commander_low_prio_loop ( void * arg )
2013-03-25 14:53:54 -07:00
{
/* Set thread name */
2013-07-31 20:58:27 +04:00
prctl ( PR_SET_NAME , " commander_low_prio " , getpid ( ) ) ;
2013-03-25 14:53:54 -07:00
2013-08-15 09:52:22 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-03-25 14:53:54 -07:00
while ( ! thread_should_exit ) {
switch ( low_prio_task ) {
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_PARAM_LOAD :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
if ( 0 = = param_load_default ( ) ) {
2013-07-31 20:58:27 +04:00
mavlink_log_info ( mavlink_fd , " [cmd] parameters loaded " ) ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
} else {
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] parameters load ERROR " ) ;
2013-07-28 23:12:16 +04:00
tune_error ( ) ;
}
2013-08-07 20:21:49 +02:00
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_PARAM_SAVE :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
if ( 0 = = param_save_default ( ) ) {
2013-07-31 20:58:27 +04:00
mavlink_log_info ( mavlink_fd , " [cmd] parameters saved " ) ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
} else {
2013-07-31 20:58:27 +04:00
mavlink_log_critical ( mavlink_fd , " [cmd] parameters save error " ) ;
2013-07-28 23:12:16 +04:00
tune_error ( ) ;
}
2013-08-07 20:21:49 +02:00
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_GYRO_CALIBRATION :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
do_gyro_calibration ( mavlink_fd ) ;
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_MAG_CALIBRATION :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
do_mag_calibration ( mavlink_fd ) ;
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_ALTITUDE_CALIBRATION :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
// do_baro_calibration(mavlink_fd);
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-31 20:58:27 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_RC_CALIBRATION :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
// do_rc_calibration(mavlink_fd);
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
case LOW_PRIO_TASK_ACCEL_CALIBRATION :
2013-03-25 14:53:54 -07:00
2013-07-28 23:12:16 +04:00
do_accel_calibration ( mavlink_fd ) ;
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
case LOW_PRIO_TASK_AIRSPEED_CALIBRATION :
do_airspeed_calibration ( mavlink_fd ) ;
2013-08-14 13:29:42 +02:00
low_prio_task = LOW_PRIO_TASK_NONE ;
2013-07-28 23:12:16 +04:00
break ;
case LOW_PRIO_TASK_NONE :
default :
/* slow down to 10Hz */
usleep ( 100000 ) ;
break ;
2013-03-25 14:53:54 -07:00
}
}
return 0 ;
}