2012-08-04 15:12:36 -07:00
/****************************************************************************
*
2016-02-25 07:53:12 +00:00
* Copyright ( c ) 2013 - 2016 PX4 Development Team . All rights reserved .
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
2016-02-13 11:40:41 +01:00
*
* Main state machine / business logic
2012-10-23 13:15:36 +02:00
*
2016-02-05 13:06:51 +01:00
* @ author Petri Tanskanen < petri . tanskanen @ inf . ethz . ch >
* @ author Lorenz Meier < lorenz @ px4 . io >
* @ author Thomas Gubler < thomas @ px4 . io >
2016-02-25 07:53:12 +00:00
* @ author Julian Oes < julian @ oes . ch >
2016-02-05 13:06:51 +01:00
* @ author Anton Babushkin < anton @ px4 . io >
* @ author Sander Smeets < sander @ droneslab . com >
2012-08-04 15:12:36 -07:00
*/
2016-06-14 13:42:49 -04:00
/* commander module headers */
# include "accelerometer_calibration.h"
# include "airspeed_calibration.h"
# include "baro_calibration.h"
# include "calibration_routines.h"
# include "commander_helper.h"
# include "esc_calibration.h"
# include "gyro_calibration.h"
# include "mag_calibration.h"
# include "PreflightCheck.h"
# include "px4_custom_mode.h"
# include "rc_calibration.h"
# include "state_machine_helper.h"
/* PX4 headers */
# include <dataman/dataman.h>
# include <drivers/drv_hrt.h>
# include <drivers/drv_led.h>
# include <drivers/drv_tone_alarm.h>
# include <geo/geo.h>
# include <navigator/navigation.h>
2015-03-11 12:16:44 -07:00
# include <px4_config.h>
2015-04-24 01:24:31 -07:00
# include <px4_posix.h>
2015-09-11 21:48:36 +02:00
# include <px4_tasks.h>
2016-06-14 13:42:49 -04:00
# include <px4_time.h>
2014-05-25 20:34:32 +02:00
# include <systemlib/circuit_breaker.h>
2016-06-14 13:42:49 -04:00
# include <systemlib/err.h>
2016-03-15 18:25:02 +00:00
# include <systemlib/mavlink_log.h>
2016-06-14 13:42:49 -04:00
# include <systemlib/param/param.h>
# include <systemlib/rc_check.h>
# include <systemlib/state_table.h>
# include <systemlib/systemlib.h>
2016-07-17 17:00:59 +01:00
# include <systemlib/hysteresis/hysteresis.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/actuator_armed.h>
# include <uORB/topics/actuator_controls.h>
2013-01-01 13:30:24 +01:00
# include <uORB/topics/battery_status.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/cpuload.h>
# include <uORB/topics/differential_pressure.h>
# include <uORB/topics/geofence_result.h>
# include <uORB/topics/home_position.h>
2012-09-21 12:55:41 +02:00
# include <uORB/topics/manual_control_setpoint.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/mavlink_log.h>
# include <uORB/topics/mission.h>
# include <uORB/topics/mission_result.h>
2015-02-13 23:19:43 +01:00
# include <uORB/topics/offboard_control_mode.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/position_setpoint_triplet.h>
2016-05-19 23:46:06 +02:00
# include <uORB/topics/vehicle_roi.h>
# include <uORB/topics/parameter_update.h>
2013-07-15 22:15:15 +02:00
# include <uORB/topics/safety.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/sensor_combined.h>
# include <uORB/topics/subsystem_info.h>
2014-05-25 08:22:54 +02:00
# include <uORB/topics/system_power.h>
2014-06-16 17:34:21 +02:00
# include <uORB/topics/telemetry_status.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/vehicle_attitude.h>
# include <uORB/topics/vehicle_command.h>
2015-12-12 13:01:49 +01:00
# include <uORB/topics/vehicle_command_ack.h>
2016-06-14 13:42:49 -04:00
# include <uORB/topics/vehicle_global_position.h>
# include <uORB/topics/vehicle_gps_position.h>
# include <uORB/topics/vehicle_land_detected.h>
# include <uORB/topics/vehicle_local_position.h>
# include <uORB/topics/vtol_vehicle_status.h>
# include <uORB/uORB.h>
2013-03-11 10:39:57 -07:00
2016-06-14 13:42:49 -04:00
/* oddly, ERROR is not defined for c++ */
# ifdef ERROR
# undef ERROR
# endif
static const int ERROR = - 1 ;
2012-09-11 23:35:01 +02:00
2016-07-01 18:04:09 +02:00
typedef enum VEHICLE_MODE_FLAG
{
VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 , /* 0b00000001 Reserved for future use. | */
VEHICLE_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. | */
VEHICLE_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. | */
VEHICLE_MODE_FLAG_GUIDED_ENABLED = 8 , /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
VEHICLE_MODE_FLAG_STABILIZE_ENABLED = 16 , /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
VEHICLE_MODE_FLAG_HIL_ENABLED = 32 , /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 , /* 0b01000000 remote control input is enabled. | */
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128 , /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
VEHICLE_MODE_FLAG_ENUM_END = 129 , /* | */
} VEHICLE_MODE_FLAG ;
2015-05-14 19:29:35 +02:00
static constexpr uint8_t COMMANDER_MAX_GPS_NOISE = 60 ; /**< Maximum percentage signal to noise ratio allowed for GPS reception */
2016-05-20 07:57:20 -06:00
/* Decouple update interval and hysteresis counters, all depends on intervals */
2016-05-09 23:01:06 +02:00
# define COMMANDER_MONITORING_INTERVAL 10000
2012-08-04 15:12:36 -07:00
# define COMMANDER_MONITORING_LOOPSPERMSEC (1 / (COMMANDER_MONITORING_INTERVAL / 1000.0f))
2013-11-05 19:56:33 +01:00
# define MAVLINK_OPEN_INTERVAL 50000
2014-04-03 20:23:34 +04:00
# define STICK_ON_OFF_LIMIT 0.9f
2012-08-04 15:12:36 -07:00
2015-03-03 13:29:32 +01:00
# define POSITION_TIMEOUT (1 * 1000 * 1000) /**< consider the local or global position estimate invalid after 1000ms */
2014-05-07 08:42:57 +02:00
# define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
2014-05-16 12:12:43 +02:00
# define OFFBOARD_TIMEOUT 500000
2014-05-07 08:42:57 +02:00
# define DIFFPRESS_TIMEOUT 2000000
2013-03-11 10:39:57 -07:00
2016-02-16 21:10:35 +01:00
# define HOTPLUG_SENS_TIMEOUT (8 * 1000 * 1000) /**< wait for hotplug sensors to come online for upto 8 seconds */
2015-11-10 19:33:14 +05:30
2013-07-31 20:58:27 +04:00
# define PRINT_INTERVAL 5000000
2016-03-06 12:34:31 +01:00
# define PRINT_MODE_REJECT_INTERVAL 500000
2015-06-08 16:48:42 +02:00
2015-11-29 18:49:58 +01:00
# define INAIR_RESTART_HOLDOFF_INTERVAL 500000
2013-07-31 20:58:27 +04:00
2015-06-06 15:03:03 -06:00
# define HIL_ID_MIN 1000
# define HIL_ID_MAX 1999
2013-07-31 20:58:27 +04:00
2016-03-15 18:25:02 +00:00
/* Mavlink log uORB handle */
static orb_advert_t mavlink_log_pub = 0 ;
2013-02-16 13:40:09 -08:00
2015-04-03 18:50:44 +02:00
/* System autostart ID */
2014-12-02 10:47:07 +01:00
static int autostart_id ;
2013-02-16 13:40:09 -08:00
/* flags */
2012-08-04 15:12:36 -07:00
static bool commander_initialized = false ;
2015-03-23 10:52:32 -07:00
static volatile bool thread_should_exit = false ; /**< daemon exit flag */
2013-09-08 20:05:15 +02:00
static volatile bool thread_running = false ; /**< daemon status flag */
2015-03-23 10:52:32 -07:00
static int daemon_task ; /**< Handle of daemon task / thread */
2015-04-03 16:14:04 +02:00
static bool need_param_autosave = false ; /**< Flag set to true if parameters should be autosaved in next iteration (happens on param update and if functionality is enabled) */
2015-11-04 18:23:19 +01:00
static bool _usb_telemetry_active = false ;
2015-06-08 17:18:25 +02:00
static hrt_abstime commander_boot_timestamp = 0 ;
2013-02-16 13:40:09 -08:00
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 ;
2016-07-17 17:00:59 +01:00
static systemlib : : Hysteresis auto_disarm_hysteresis ( false ) ;
2013-07-31 20:58:27 +04:00
2014-07-29 17:50:52 +02:00
static float eph_threshold = 5.0f ;
static float epv_threshold = 10.0f ;
2012-09-21 12:55:41 +02:00
2016-04-23 14:29:25 +02:00
static struct vehicle_status_s status = { } ;
2016-05-19 23:46:06 +02:00
static struct vehicle_roi_s _roi = { } ;
2016-04-23 14:29:25 +02:00
static struct battery_status_s battery = { } ;
static struct actuator_armed_s armed = { } ;
static struct safety_s safety = { } ;
static struct vehicle_control_mode_s control_mode = { } ;
static struct offboard_control_mode_s offboard_control_mode = { } ;
static struct home_position_s _home = { } ;
2016-03-13 15:39:35 +01:00
static int32_t _flight_mode_slots [ manual_control_setpoint_s : : MODE_SLOT_MAX ] ;
2016-04-23 14:29:25 +02:00
static struct commander_state_s internal_state = { } ;
2014-01-16 10:58:05 +01:00
2016-04-22 21:52:47 +02:00
static uint8_t main_state_before_rtl = commander_state_s : : MAIN_STATE_MAX ;
2015-06-13 18:37:19 +02:00
static unsigned _last_mission_instance = 0 ;
2016-05-09 23:01:06 +02:00
struct manual_control_setpoint_s sp_man = { } ; ///< the current manual control setpoint
static manual_control_setpoint_s _last_sp_man = { } ; ///< the manual control setpoint valid at the last mode switch
2015-06-13 18:37:19 +02:00
2016-03-06 14:56:25 +01:00
static struct vtol_vehicle_status_s vtol_status = { } ;
2016-02-26 18:14:03 -08:00
static struct cpuload_s cpuload = { } ;
2015-08-07 16:43:16 +02:00
2016-02-25 07:56:28 +00:00
2016-02-25 08:11:57 +00:00
static uint8_t main_state_prev = 0 ;
2016-04-23 00:30:50 +02:00
static bool rtl_on = false ;
2016-02-25 08:11:57 +00:00
2016-02-25 17:00:39 +00:00
static struct status_flags_s status_flags = { } ;
2016-02-26 11:01:12 +00:00
static uint64_t rc_signal_lost_timestamp ; // Time at which the RC reception was lost
static float avionics_power_rail_voltage ; // voltage of the avionics power rail
2016-06-07 16:00:23 +02:00
static bool can_arm_without_gps = false ;
2016-02-26 11:01:12 +00: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 .
*/
2014-10-23 16:17:20 +02:00
bool handle_command ( struct vehicle_status_s * status , const struct safety_s * safety , struct vehicle_command_s * cmd ,
struct actuator_armed_s * armed , struct home_position_s * home , struct vehicle_global_position_s * global_pos ,
2015-12-12 13:01:49 +01:00
struct vehicle_local_position_s * local_pos , struct vehicle_attitude_s * attitude , orb_advert_t * home_pub ,
2016-05-19 23:46:06 +02:00
orb_advert_t * command_ack_pub , struct vehicle_command_ack_s * command_ack , struct vehicle_roi_s * roi ,
orb_advert_t * roi_pub ) ;
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 [ ] ) ;
2016-02-24 18:08:56 +00:00
void control_status_leds ( vehicle_status_s * status_local , const actuator_armed_s * actuator_armed , bool changed ,
2016-05-06 11:11:29 +02:00
battery_status_s * battery_local , const cpuload_s * cpuload_local ) ;
2013-08-27 23:08:00 +02:00
2015-04-27 13:29:36 +02:00
void get_circuit_breaker_params ( ) ;
2013-08-17 12:37:41 +02:00
void check_valid ( hrt_abstime timestamp , hrt_abstime timeout , bool valid_in , bool * valid_out , bool * changed ) ;
2013-07-31 20:58:27 +04:00
2016-05-09 23:01:06 +02:00
transition_result_t set_main_state_rc ( struct vehicle_status_s * status ) ;
2013-07-28 23:12:16 +04:00
2014-01-27 20:49:17 +01:00
void set_control_mode ( ) ;
2015-08-19 17:54:57 +02:00
bool stabilization_required ( ) ;
2014-02-01 13:21:51 +01:00
void print_reject_mode ( struct vehicle_status_s * current_status , const char * msg ) ;
2013-08-27 23:08:00 +02:00
2013-08-16 09:23:39 +02:00
void print_reject_arm ( const char * msg ) ;
2013-07-31 20:58:27 +04:00
2013-08-17 15:47:42 +02:00
void print_status ( ) ;
2016-03-15 18:25:02 +00:00
transition_result_t arm_disarm ( bool arm , orb_advert_t * mavlink_log_pub , const char * armedBy ) ;
2014-03-16 21:38:23 -07:00
2015-01-16 16:43:11 +01:00
/**
* @ brief This function initializes the home position of the vehicle . This happens first time we get a good GPS fix and each
* time the vehicle is armed with a good GPS fix .
* */
2015-01-16 16:46:16 +01:00
static void commander_set_home_position ( orb_advert_t & homePub , home_position_s & home ,
2015-10-27 09:58:54 +01:00
const vehicle_local_position_s & localPosition , const vehicle_global_position_s & globalPosition ,
const vehicle_attitude_s & attitude ) ;
2015-01-16 16:43:11 +01:00
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 ) ;
2015-12-12 13:01:49 +01:00
void answer_command ( struct vehicle_command_s & cmd , unsigned result ,
orb_advert_t & command_ack_pub , vehicle_command_ack_s & command_ack ) ;
2013-08-27 23:08:00 +02:00
2015-06-10 11:05:56 -06:00
/**
* check whether autostart ID is in the reserved range for HIL setups
*/
2016-06-14 13:42:49 -04:00
static bool is_hil_setup ( int id ) {
2015-06-10 11:05:56 -06:00
return ( id > = HIL_ID_MIN ) & & ( id < = HIL_ID_MAX ) ;
}
2013-07-16 09:35:31 +02:00
int commander_main ( int argc , char * argv [ ] )
{
2015-03-17 13:37:01 -04:00
if ( argc < 2 ) {
2013-07-16 09:35:31 +02:00
usage ( " missing command " ) ;
2015-04-15 19:38:59 -07:00
return 1 ;
2014-05-11 13:36:51 +02:00
}
2013-07-16 09:35:31 +02:00
if ( ! strcmp ( argv [ 1 ] , " start " ) ) {
if ( thread_running ) {
2015-08-11 09:24:13 +02:00
warnx ( " already running " ) ;
2013-07-16 09:35:31 +02:00
/* this is not an error */
2015-04-15 19:38:59 -07:00
return 0 ;
2013-07-16 09:35:31 +02:00
}
thread_should_exit = false ;
2015-05-06 14:43:11 -07:00
daemon_task = px4_task_spawn_cmd ( " commander " ,
2013-07-28 23:12:16 +04:00
SCHED_DEFAULT ,
2015-11-29 17:05:01 +01:00
SCHED_PRIORITY_DEFAULT + 40 ,
2016-08-29 23:36:34 +02:00
3100 ,
2013-07-28 23:12:16 +04:00
commander_thread_main ,
2015-08-26 16:17:07 +02:00
( char * const * ) & argv [ 0 ] ) ;
2013-09-08 20:05:15 +02:00
2015-08-11 09:24:13 +02:00
unsigned constexpr max_wait_us = 1000000 ;
unsigned constexpr max_wait_steps = 2000 ;
unsigned i ;
for ( i = 0 ; i < max_wait_steps ; i + + ) {
usleep ( max_wait_us / max_wait_steps ) ;
if ( thread_running ) {
break ;
}
2013-09-08 20:05:15 +02:00
}
2015-08-11 11:03:01 +02:00
return ! ( i < max_wait_steps ) ;
2013-07-16 09:35:31 +02:00
}
2012-08-04 15:12:36 -07:00
2013-07-16 09:35:31 +02:00
if ( ! strcmp ( argv [ 1 ] , " stop " ) ) {
2013-09-08 20:05:15 +02:00
2014-05-11 13:36:51 +02:00
if ( ! thread_running ) {
2015-04-15 19:38:59 -07:00
warnx ( " commander already stopped " ) ;
return 0 ;
2014-05-11 13:36:51 +02:00
}
2013-09-08 20:05:15 +02:00
2013-07-16 09:35:31 +02:00
thread_should_exit = true ;
2013-09-08 20:05:15 +02:00
while ( thread_running ) {
usleep ( 200000 ) ;
warnx ( " . " ) ;
}
warnx ( " terminated. " ) ;
2015-04-15 19:38:59 -07:00
return 0 ;
2013-07-16 09:35:31 +02:00
}
2013-03-25 14:53:54 -07:00
2014-07-11 14:51:13 +02:00
/* commands needing the app to run below */
if ( ! thread_running ) {
warnx ( " \t commander not started " ) ;
2015-04-15 19:38:59 -07:00
return 1 ;
2014-07-11 14:51:13 +02:00
}
2013-07-16 09:35:31 +02:00
2014-07-11 14:51:13 +02:00
if ( ! strcmp ( argv [ 1 ] , " status " ) ) {
print_status ( ) ;
2015-04-15 19:38:59 -07:00
return 0 ;
2014-07-11 14:51:13 +02:00
}
2013-07-16 09:35:31 +02:00
2015-02-09 13:56:53 +01:00
if ( ! strcmp ( argv [ 1 ] , " calibrate " ) ) {
if ( argc > 2 ) {
int calib_ret = OK ;
if ( ! strcmp ( argv [ 2 ] , " mag " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_mag_calibration ( & mavlink_log_pub ) ;
2015-02-09 13:56:53 +01:00
} else if ( ! strcmp ( argv [ 2 ] , " accel " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_accel_calibration ( & mavlink_log_pub ) ;
2015-02-09 13:56:53 +01:00
} else if ( ! strcmp ( argv [ 2 ] , " gyro " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_gyro_calibration ( & mavlink_log_pub ) ;
2015-05-19 14:20:00 +02:00
} else if ( ! strcmp ( argv [ 2 ] , " level " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_level_calibration ( & mavlink_log_pub ) ;
2015-05-22 09:28:52 -07:00
} else if ( ! strcmp ( argv [ 2 ] , " esc " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_esc_calibration ( & mavlink_log_pub , & armed ) ;
2015-11-17 12:59:45 +01:00
} else if ( ! strcmp ( argv [ 2 ] , " airspeed " ) ) {
2016-03-15 18:25:02 +00:00
calib_ret = do_airspeed_calibration ( & mavlink_log_pub ) ;
2015-02-09 13:56:53 +01:00
} else {
warnx ( " argument %s unsupported. " , argv [ 2 ] ) ;
}
if ( calib_ret ) {
2015-04-15 19:38:59 -07:00
warnx ( " calibration failed, exiting. " ) ;
2015-08-26 16:17:07 +02:00
return 1 ;
2015-02-09 13:56:53 +01:00
} else {
2015-04-15 19:38:59 -07:00
return 0 ;
2015-02-09 13:56:53 +01:00
}
} else {
warnx ( " missing argument " ) ;
}
}
2014-07-11 14:51:13 +02:00
if ( ! strcmp ( argv [ 1 ] , " check " ) ) {
2015-11-10 19:33:14 +05:30
int checkres = 0 ;
2016-06-07 16:00:23 +02:00
checkres = preflight_check ( & status , & mavlink_log_pub , false , true , & status_flags , & battery , false ) ;
2015-11-10 19:33:14 +05:30
warnx ( " Preflight check: %s " , ( checkres = = 0 ) ? " OK " : " FAILED " ) ;
2016-06-07 16:00:23 +02:00
checkres = preflight_check ( & status , & mavlink_log_pub , true , true , & status_flags , & battery , true ) ;
2015-11-10 19:33:14 +05:30
warnx ( " Prearm check: %s " , ( checkres = = 0 ) ? " OK " : " FAILED " ) ;
2015-04-15 19:38:59 -07:00
return 0 ;
2013-07-16 09:35:31 +02:00
}
2014-01-16 10:58:05 +01:00
if ( ! strcmp ( argv [ 1 ] , " arm " ) ) {
2016-03-15 18:25:02 +00:00
if ( TRANSITION_CHANGED ! = arm_disarm ( true , & mavlink_log_pub , " command line " ) ) {
2015-11-14 15:02:56 +01:00
warnx ( " arming failed " ) ;
}
2015-04-15 19:38:59 -07:00
return 0 ;
2014-01-16 10:58:05 +01:00
}
2014-07-11 14:55:46 +02:00
if ( ! strcmp ( argv [ 1 ] , " disarm " ) ) {
2016-03-15 18:25:02 +00:00
if ( TRANSITION_DENIED = = arm_disarm ( false , & mavlink_log_pub , " command line " ) ) {
2015-11-14 15:02:56 +01:00
warnx ( " rejected disarm " ) ;
}
2015-08-26 16:17:07 +02:00
return 0 ;
2014-01-16 10:58:05 +01:00
}
2015-11-20 11:15:17 +01:00
if ( ! strcmp ( argv [ 1 ] , " takeoff " ) ) {
2015-12-20 20:29:22 +01:00
/* see if we got a home position */
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_home_position_valid ) {
2015-12-20 20:29:22 +01:00
2016-03-15 18:25:02 +00:00
if ( TRANSITION_DENIED ! = arm_disarm ( true , & mavlink_log_pub , " command line " ) ) {
2015-12-20 20:29:22 +01:00
2015-11-20 11:15:17 +01:00
vehicle_command_s cmd = { } ;
2015-11-21 22:20:13 +01:00
cmd . target_system = status . system_id ;
cmd . target_component = status . component_id ;
2015-11-20 11:15:17 +01:00
cmd . command = vehicle_command_s : : VEHICLE_CMD_NAV_TAKEOFF ;
2016-05-13 22:05:46 +02:00
cmd . param1 = NAN ; /* minimum pitch */
/* param 2-3 unused */
cmd . param2 = NAN ;
cmd . param3 = NAN ;
cmd . param4 = NAN ;
cmd . param5 = NAN ;
cmd . param6 = NAN ;
cmd . param7 = NAN ;
orb_advert_t h = orb_advertise ( ORB_ID ( vehicle_command ) , & cmd ) ;
( void ) orb_unadvertise ( h ) ;
2015-11-20 11:15:17 +01:00
} else {
2015-12-20 20:29:22 +01:00
warnx ( " arming failed " ) ;
2015-11-20 11:15:17 +01:00
}
} else {
2015-12-20 20:29:22 +01:00
warnx ( " rejecting takeoff, no position lock yet. Please retry.. " ) ;
2015-11-20 11:15:17 +01:00
}
2015-12-20 20:29:22 +01:00
2015-11-20 11:15:17 +01:00
return 0 ;
}
2015-12-28 16:00:32 +01:00
if ( ! strcmp ( argv [ 1 ] , " land " ) ) {
vehicle_command_s cmd = { } ;
cmd . target_system = status . system_id ;
cmd . target_component = status . component_id ;
cmd . command = vehicle_command_s : : VEHICLE_CMD_NAV_LAND ;
2016-05-13 22:05:46 +02:00
/* param 2-3 unused */
cmd . param2 = NAN ;
cmd . param3 = NAN ;
cmd . param4 = NAN ;
cmd . param5 = NAN ;
cmd . param6 = NAN ;
cmd . param7 = NAN ;
orb_advert_t h = orb_advertise ( ORB_ID ( vehicle_command ) , & cmd ) ;
( void ) orb_unadvertise ( h ) ;
2015-12-28 16:00:32 +01:00
return 0 ;
}
2016-06-15 20:42:56 +02:00
if ( ! strcmp ( argv [ 1 ] , " transition " ) ) {
vehicle_command_s cmd = { } ;
cmd . target_system = status . system_id ;
cmd . target_component = status . component_id ;
cmd . command = vehicle_command_s : : VEHICLE_CMD_DO_VTOL_TRANSITION ;
/* transition to the other mode */
cmd . param1 = ( status . is_rotary_wing ) ? vtol_vehicle_status_s : : VEHICLE_VTOL_STATE_FW : vtol_vehicle_status_s : : VEHICLE_VTOL_STATE_MC ;
/* param 2-3 unused */
cmd . param2 = NAN ;
cmd . param3 = NAN ;
cmd . param4 = NAN ;
cmd . param5 = NAN ;
cmd . param6 = NAN ;
cmd . param7 = NAN ;
orb_advert_t h = orb_advertise ( ORB_ID ( vehicle_command ) , & cmd ) ;
( void ) orb_unadvertise ( h ) ;
return 0 ;
}
2016-03-10 11:48:02 -05:00
if ( ! strcmp ( argv [ 1 ] , " mode " ) ) {
if ( argc > 2 ) {
2016-04-04 13:23:30 +02:00
uint8_t new_main_state = commander_state_s : : MAIN_STATE_MAX ;
2016-03-10 11:48:02 -05:00
if ( ! strcmp ( argv [ 2 ] , " manual " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_MANUAL ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " altctl " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_ALTCTL ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " posctl " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_POSCTL ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " auto:mission " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_AUTO_MISSION ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " auto:loiter " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " auto:rtl " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_AUTO_RTL ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " acro " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_ACRO ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " offboard " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_OFFBOARD ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " stabilized " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_STAB ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " rattitude " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_RATTITUDE ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " auto:takeoff " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_AUTO_TAKEOFF ;
2016-03-10 11:48:02 -05:00
} else if ( ! strcmp ( argv [ 2 ] , " auto:land " ) ) {
2016-04-04 13:23:30 +02:00
new_main_state = commander_state_s : : MAIN_STATE_AUTO_LAND ;
2016-03-10 11:48:02 -05:00
} else {
warnx ( " argument %s unsupported. " , argv [ 2 ] ) ;
}
2016-04-22 15:15:37 -04:00
if ( TRANSITION_DENIED = = main_state_transition ( & status , new_main_state , main_state_prev , & status_flags , & internal_state ) ) {
2016-03-10 11:48:02 -05:00
warnx ( " mode change failed " ) ;
}
return 0 ;
} else {
warnx ( " missing argument " ) ;
}
}
2016-02-22 22:15:12 +01:00
if ( ! strcmp ( argv [ 1 ] , " lockdown " ) ) {
2016-02-23 13:06:41 +01:00
if ( argc < 3 ) {
usage ( " not enough arguments, missing [on, off] " ) ;
return 1 ;
}
2016-02-22 22:15:12 +01:00
vehicle_command_s cmd = { } ;
cmd . target_system = status . system_id ;
cmd . target_component = status . component_id ;
cmd . command = vehicle_command_s : : VEHICLE_CMD_DO_FLIGHTTERMINATION ;
2016-02-23 13:06:41 +01:00
/* if the comparison matches for off (== 0) set 0.0f, 2.0f (on) else */
cmd . param1 = strcmp ( argv [ 2 ] , " off " ) ? 2.0f : 0.0f ; /* lockdown */
2016-02-22 22:15:12 +01:00
// XXX inspect use of publication handle
( void ) orb_advertise ( ORB_ID ( vehicle_command ) , & cmd ) ;
return 0 ;
}
2013-07-16 09:35:31 +02:00
usage ( " unrecognized command " ) ;
2015-04-15 19:38:59 -07:00
return 1 ;
2013-07-16 09:35:31 +02:00
}
void usage ( const char * reason )
{
2015-11-03 22:53:03 +01:00
if ( reason & & * reason > 0 ) {
PX4_INFO ( " %s " , reason ) ;
2014-05-11 13:36:51 +02:00
}
2013-07-16 09:35:31 +02:00
2016-06-15 20:42:56 +02:00
PX4_INFO ( " usage: commander {start|stop|status|calibrate|check|arm|disarm|takeoff|land|transition|mode} \n " ) ;
2013-07-16 09:35:31 +02:00
}
2013-02-24 21:57:38 +01:00
2013-08-27 23:08:00 +02:00
void print_status ( )
{
2015-02-27 19:31:04 +01:00
warnx ( " type: %s " , ( status . is_rotary_wing ) ? " symmetric motion " : " forward motion " ) ;
2016-04-21 10:36:14 +02:00
warnx ( " safety: USB enabled: %s, power state valid: %s " , ( status_flags . usb_connected ) ? " [OK] " : " [NO] " ,
2016-02-26 11:01:12 +00:00
( status_flags . condition_power_input_valid ) ? " [OK] " : " [NO] " ) ;
warnx ( " avionics rail: %6.2f V " , ( double ) avionics_power_rail_voltage ) ;
2015-12-28 15:13:09 +01:00
warnx ( " home: lat = %.7f, lon = %.7f, alt = %.2f, yaw: %.2f " , _home . lat , _home . lon , ( double ) _home . alt , ( double ) _home . yaw ) ;
2015-06-08 15:19:41 +02:00
warnx ( " home: x = %.7f, y = %.7f, z = %.2f " , ( double ) _home . x , ( double ) _home . y , ( double ) _home . z ) ;
2016-03-13 19:49:18 +01:00
warnx ( " datalink: %s " , ( status . data_link_lost ) ? " LOST " : " OK " ) ;
# ifdef __PX4_POSIX
2016-04-04 13:23:30 +02:00
warnx ( " main state: %d " , internal_state . main_state ) ;
2016-03-13 19:49:18 +01:00
warnx ( " nav state: %d " , status . nav_state ) ;
# endif
2013-08-18 12:42:24 +02:00
/* read all relevant states */
int state_sub = orb_subscribe ( ORB_ID ( vehicle_status ) ) ;
struct vehicle_status_s state ;
orb_copy ( ORB_ID ( vehicle_status ) , state_sub , & state ) ;
2013-08-27 23:08:00 +02:00
const char * armed_str ;
2013-08-18 12:42:24 +02:00
2016-02-26 15:41:03 +00:00
switch ( status . arming_state ) {
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_INIT :
2013-08-27 23:08:00 +02:00
armed_str = " INIT " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_STANDBY :
2013-08-27 23:08:00 +02:00
armed_str = " STANDBY " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_ARMED :
2013-08-27 23:08:00 +02:00
armed_str = " ARMED " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_ARMED_ERROR :
2013-08-27 23:08:00 +02:00
armed_str = " ARMED_ERROR " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_STANDBY_ERROR :
2013-08-27 23:08:00 +02:00
armed_str = " STANDBY_ERROR " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_REBOOT :
2013-08-27 23:08:00 +02:00
armed_str = " REBOOT " ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : ARMING_STATE_IN_AIR_RESTORE :
2013-08-27 23:08:00 +02:00
armed_str = " IN_AIR_RESTORE " ;
break ;
default :
armed_str = " ERR: UNKNOWN STATE " ;
break ;
2013-08-18 12:42:24 +02:00
}
2015-07-01 11:05:45 -07:00
px4_close ( state_sub ) ;
2013-09-01 10:29:30 +02:00
2013-08-18 12:42:24 +02:00
warnx ( " arming: %s " , armed_str ) ;
2013-08-17 15:47:42 +02:00
}
2013-09-08 21:06:55 +02:00
static orb_advert_t status_pub ;
2016-03-15 18:25:02 +00:00
transition_result_t arm_disarm ( bool arm , orb_advert_t * mavlink_log_pub_local , const char * armedBy )
2014-01-16 10:58:05 +01:00
{
2014-05-11 13:36:51 +02:00
transition_result_t arming_res = TRANSITION_NOT_CHANGED ;
2015-06-06 10:34:01 -06:00
// For HIL platforms, require that simulated sensors are connected
2015-06-12 15:58:21 +02:00
if ( arm & & hrt_absolute_time ( ) > commander_boot_timestamp + INAIR_RESTART_HOLDOFF_INTERVAL & &
is_hil_setup ( autostart_id ) & & status . hil_state ! = vehicle_status_s : : HIL_STATE_ON ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_critical ( mavlink_log_pub_local , " HIL platform: Connect to simulator before arming " ) ;
2015-06-06 10:34:01 -06:00
return TRANSITION_DENIED ;
}
2016-04-04 13:23:30 +02:00
// Transition the armed state. By passing mavlink_log_pub to arming_state_transition it will
2016-02-24 08:00:33 +00:00
// output appropriate error messages if the state cannot transition.
2016-04-07 16:19:20 +02:00
arming_res = arming_state_transition ( & status ,
& battery ,
& safety ,
2016-02-24 08:00:33 +00:00
arm ? vehicle_status_s : : ARMING_STATE_ARMED : vehicle_status_s : : ARMING_STATE_STANDBY ,
& armed ,
true /* fRunPreArmChecks */ ,
mavlink_log_pub_local ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ;
2014-05-11 13:36:51 +02:00
2016-03-15 18:25:02 +00:00
if ( arming_res = = TRANSITION_CHANGED ) {
mavlink_log_info ( mavlink_log_pub_local , " [cmd] %s by %s " , arm ? " ARMED " : " DISARMED " , armedBy ) ;
2014-05-11 13:36:51 +02:00
} else if ( arming_res = = TRANSITION_DENIED ) {
tune_negative ( true ) ;
}
return arming_res ;
2014-01-16 10:58:05 +01:00
}
2014-07-13 11:41:39 +02:00
bool handle_command ( struct vehicle_status_s * status_local , const struct safety_s * safety_local ,
2014-10-23 16:17:20 +02:00
struct vehicle_command_s * cmd , struct actuator_armed_s * armed_local ,
2015-06-08 17:18:25 +02:00
struct home_position_s * home , struct vehicle_global_position_s * global_pos ,
2015-12-12 13:01:49 +01:00
struct vehicle_local_position_s * local_pos , struct vehicle_attitude_s * attitude , orb_advert_t * home_pub ,
2016-05-19 23:46:06 +02:00
orb_advert_t * command_ack_pub , struct vehicle_command_ack_s * command_ack ,
struct vehicle_roi_s * roi , orb_advert_t * roi_pub )
2012-08-04 15:12:36 -07:00
{
2014-04-08 17:06:52 +02:00
/* only handle commands that are meant to be handled by this system and component */
2014-10-23 16:17:20 +02:00
if ( cmd - > target_system ! = status_local - > system_id | | ( ( cmd - > target_component ! = status_local - > component_id )
& & ( cmd - > target_component ! = 0 ) ) ) { // component_id 0: valid for all components
2014-04-08 17:06:52 +02:00
return false ;
}
2014-05-27 21:56:32 +02:00
/* result of the command */
2015-05-26 22:55:14 -07:00
unsigned cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_UNSUPPORTED ;
2013-08-17 18:39:46 +02:00
2012-08-04 15:12:36 -07:00
/* request to set different system mode */
switch ( cmd - > command ) {
2016-04-23 20:12:27 +02:00
case vehicle_command_s : : VEHICLE_CMD_DO_REPOSITION : {
// Just switch the flight mode here, the navigator takes care of
// doing something sensible with the coordinates. Its designed
// to not require navigator and command to receive / process
// the data at the exact same time.
2016-04-24 11:54:50 +02:00
// Check if a mode switch had been requested
2016-05-09 23:01:06 +02:00
if ( ( ( ( uint32_t ) cmd - > param2 ) & 1 ) > 0 ) {
2016-04-24 11:54:50 +02:00
transition_result_t main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ;
if ( ( main_ret ! = TRANSITION_DENIED ) ) {
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2016-04-23 20:12:27 +02:00
2016-04-24 11:54:50 +02:00
} else {
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
mavlink_log_critical ( & mavlink_log_pub , " Rejecting reposition command " ) ;
}
2016-04-23 20:12:27 +02:00
} else {
2016-04-24 11:54:50 +02:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2016-04-23 20:12:27 +02:00
}
}
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_DO_SET_MODE : {
2014-05-27 21:56:32 +02:00
uint8_t base_mode = ( uint8_t ) cmd - > param1 ;
uint8_t custom_main_mode = ( uint8_t ) cmd - > param2 ;
2015-11-25 16:22:23 -05:00
uint8_t custom_sub_mode = ( uint8_t ) cmd - > param3 ;
2013-08-07 20:21:49 +02:00
2014-05-27 21:56:32 +02:00
transition_result_t arming_ret = TRANSITION_NOT_CHANGED ;
2013-10-21 20:07:47 +02:00
2014-05-27 21:56:32 +02:00
transition_result_t main_ret = TRANSITION_NOT_CHANGED ;
2014-01-26 11:52:33 +01:00
2014-05-27 21:56:32 +02:00
/* set HIL state */
2016-07-01 18:04:09 +02:00
hil_state_t new_hil_state = ( base_mode & VEHICLE_MODE_FLAG_HIL_ENABLED ) ? vehicle_status_s : : HIL_STATE_ON : vehicle_status_s : : HIL_STATE_OFF ;
2016-03-15 18:25:02 +00:00
transition_result_t hil_ret = hil_state_transition ( new_hil_state , status_pub , status_local , & mavlink_log_pub ) ;
2013-09-08 21:06:55 +02:00
2014-05-27 21:56:32 +02:00
// Transition the arming state
2016-07-01 18:04:09 +02:00
bool cmd_arm = base_mode & VEHICLE_MODE_FLAG_SAFETY_ARMED ;
2015-06-11 12:22:47 +02:00
2016-03-15 18:25:02 +00:00
arming_ret = arm_disarm ( cmd_arm , & mavlink_log_pub , " set mode command " ) ;
2012-08-04 15:12:36 -07:00
2015-11-29 18:49:58 +01:00
/* update home position on arming if at least 500 ms from commander start spent to avoid setting home on in-air restart */
2015-06-11 12:22:47 +02:00
if ( cmd_arm & & ( arming_ret = = TRANSITION_CHANGED ) & &
( hrt_absolute_time ( ) > ( commander_boot_timestamp + INAIR_RESTART_HOLDOFF_INTERVAL ) ) ) {
2015-10-27 09:58:54 +01:00
commander_set_home_position ( * home_pub , * home , * local_pos , * global_pos , * attitude ) ;
2015-06-08 16:48:42 +02:00
}
2012-08-04 15:12:36 -07:00
2016-07-01 18:04:09 +02:00
if ( base_mode & VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED ) {
2014-05-27 21:56:32 +02:00
/* use autopilot-specific mode */
if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_MANUAL ) {
/* MANUAL */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2013-08-07 20:21:49 +02:00
2014-05-11 13:35:05 +02:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_ALTCTL ) {
/* ALTCTL */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_ALTCTL , main_state_prev , & status_flags , & internal_state ) ;
2012-12-27 17:13:48 +01:00
2014-05-11 13:35:05 +02:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_POSCTL ) {
/* POSCTL */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_POSCTL , main_state_prev , & status_flags , & internal_state ) ;
2012-12-27 17:13:48 +01:00
2013-08-25 20:17:42 +02:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_AUTO ) {
2013-08-07 20:21:49 +02:00
/* AUTO */
2015-11-29 19:26:45 +01:00
if ( custom_sub_mode > 0 ) {
switch ( custom_sub_mode ) {
case PX4_CUSTOM_SUB_MODE_AUTO_LOITER :
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ;
2015-11-29 19:26:45 +01:00
break ;
case PX4_CUSTOM_SUB_MODE_AUTO_MISSION :
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_MISSION , main_state_prev , & status_flags , & internal_state ) ;
2015-11-29 19:26:45 +01:00
break ;
case PX4_CUSTOM_SUB_MODE_AUTO_RTL :
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_RTL , main_state_prev , & status_flags , & internal_state ) ;
2015-11-29 19:26:45 +01:00
break ;
2015-12-02 12:04:34 +01:00
case PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF :
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_TAKEOFF , main_state_prev , & status_flags , & internal_state ) ;
2015-12-02 12:04:34 +01:00
break ;
2015-12-18 09:48:47 +01:00
case PX4_CUSTOM_SUB_MODE_AUTO_LAND :
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LAND , main_state_prev , & status_flags , & internal_state ) ;
2015-12-18 09:48:47 +01:00
break ;
2016-06-14 13:30:59 -04:00
case PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET :
2016-04-04 13:23:30 +02:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_FOLLOW_TARGET , main_state_prev , & status_flags , & internal_state ) ;
2016-02-18 06:57:01 -08:00
break ;
2015-11-29 19:26:45 +01:00
default :
main_ret = TRANSITION_DENIED ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Unsupported auto mode " ) ;
2015-11-29 19:26:45 +01:00
break ;
}
} else {
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_MISSION , main_state_prev , & status_flags , & internal_state ) ;
2015-11-25 16:22:23 -05:00
}
2014-05-20 00:03:00 +02:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_ACRO ) {
/* ACRO */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_ACRO , main_state_prev , & status_flags , & internal_state ) ;
2014-05-21 10:40:58 +02:00
2016-03-09 16:30:56 -05:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_RATTITUDE ) {
/* RATTITUDE */
2016-04-04 13:23:30 +02:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_RATTITUDE , main_state_prev , & status_flags , & internal_state ) ;
2016-03-09 16:30:56 -05:00
2015-05-17 12:58:44 +02:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_STABILIZED ) {
/* STABILIZED */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_STAB , main_state_prev , & status_flags , & internal_state ) ;
2015-05-17 12:58:44 +02:00
2014-01-29 21:21:16 +01:00
} else if ( custom_main_mode = = PX4_CUSTOM_MAIN_MODE_OFFBOARD ) {
/* OFFBOARD */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_OFFBOARD , main_state_prev , & status_flags , & internal_state ) ;
2013-08-07 20:21:49 +02:00
}
2012-12-27 17:13:48 +01:00
2014-05-27 21:56:32 +02:00
} else {
2013-08-07 20:21:49 +02:00
/* use base mode */
2016-07-01 18:04:09 +02:00
if ( base_mode & VEHICLE_MODE_FLAG_AUTO_ENABLED ) {
2013-08-07 20:21:49 +02:00
/* AUTO */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_MISSION , main_state_prev , & status_flags , & internal_state ) ;
2013-08-07 20:21:49 +02:00
2016-07-01 18:04:09 +02:00
} else if ( base_mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED ) {
if ( base_mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED ) {
2014-05-11 13:35:05 +02:00
/* POSCTL */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_POSCTL , main_state_prev , & status_flags , & internal_state ) ;
2013-08-07 20:21:49 +02:00
2016-07-01 18:04:09 +02:00
} else if ( base_mode & VEHICLE_MODE_FLAG_STABILIZE_ENABLED ) {
2015-05-17 12:58:44 +02:00
/* STABILIZED */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_STAB , main_state_prev , & status_flags , & internal_state ) ;
2015-05-17 12:58:44 +02:00
} else {
2013-07-31 20:58:27 +04:00
/* MANUAL */
2016-02-26 15:41:03 +00:00
main_ret = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-31 20:58:27 +04:00
}
2013-02-19 12:32:47 -08:00
}
2013-07-31 20:58:27 +04:00
}
2014-01-26 11:52:33 +01:00
2016-01-18 23:16:31 -08:00
if ( ( hil_ret ! = TRANSITION_DENIED ) & & ( arming_ret ! = TRANSITION_DENIED ) & & ( main_ret ! = TRANSITION_DENIED ) ) {
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2012-08-29 14:20:55 +02:00
2014-05-27 21:56:32 +02:00
} else {
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2015-10-07 16:35:51 +02:00
if ( arming_ret = = TRANSITION_DENIED ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Rejecting arming cmd " ) ;
2015-10-07 16:35:51 +02:00
}
2014-05-27 21:56:32 +02:00
}
2013-07-31 20:58:27 +04:00
}
2014-04-27 02:26:09 +02:00
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_COMPONENT_ARM_DISARM : {
2015-03-08 14:49:55 +01:00
2014-07-13 11:41:39 +02:00
// Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
// for logic state parameters
if ( static_cast < int > ( cmd - > param1 + 0.5f ) ! = 0 & & static_cast < int > ( cmd - > param1 + 0.5f ) ! = 1 ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Unsupported ARM_DISARM param: %.3f " , ( double ) cmd - > param1 ) ;
2014-05-06 14:57:06 +02:00
2014-05-11 13:36:51 +02:00
} else {
2014-07-13 11:41:39 +02:00
bool cmd_arms = ( static_cast < int > ( cmd - > param1 + 0.5f ) = = 1 ) ;
2014-05-11 13:36:51 +02:00
// Flick to inair restore first if this comes from an onboard system
2014-07-13 11:41:39 +02:00
if ( cmd - > source_system = = status_local - > system_id & & cmd - > source_component = = status_local - > component_id ) {
2016-02-26 15:41:03 +00:00
status . arming_state = vehicle_status_s : : ARMING_STATE_IN_AIR_RESTORE ;
2015-03-17 10:06:02 +01:00
2016-06-21 16:20:33 +08:00
} else {
2015-04-26 17:39:00 +02:00
// Refuse to arm if preflight checks have failed
2016-05-09 23:01:06 +02:00
if ( ( ! status_local - > hil_state ) ! = vehicle_status_s : : HIL_STATE_ON & & ! status_flags . condition_system_sensors_initialized ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Arming DENIED. Preflight checks have failed. " ) ;
2016-02-12 21:39:50 -08:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED ;
2015-03-17 10:06:02 +01:00
break ;
}
2016-02-12 21:39:50 -08:00
2016-05-09 23:01:06 +02:00
// Refuse to arm if in manual with non-zero throttle
if ( ( status_local - > nav_state = = vehicle_status_s : : NAVIGATION_STATE_MANUAL | | status_local - > nav_state = = vehicle_status_s : : NAVIGATION_STATE_STAB | |
status_local - > nav_state = = vehicle_status_s : : NAVIGATION_STATE_ACRO ) & & sp_man . z > 0.1f ) {
mavlink_log_critical ( & mavlink_log_pub , " Arming DENIED. Manual throttle non-zero. " ) ;
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED ;
break ;
}
2015-03-17 10:06:02 +01:00
}
2014-05-11 13:36:51 +02:00
2016-03-15 18:25:02 +00:00
transition_result_t arming_res = arm_disarm ( cmd_arms , & mavlink_log_pub , " arm/disarm component command " ) ;
2014-05-11 13:36:51 +02:00
if ( arming_res = = TRANSITION_DENIED ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " REJECTING component arm cmd " ) ;
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2014-05-11 13:36:51 +02:00
} else {
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2015-12-20 20:29:22 +01:00
/* update home position on arming if at least 500 ms from commander start spent to avoid setting home on in-air restart */
if ( cmd_arms & & ( arming_res = = TRANSITION_CHANGED ) & &
( hrt_absolute_time ( ) > ( commander_boot_timestamp + INAIR_RESTART_HOLDOFF_INTERVAL ) ) ) {
commander_set_home_position ( * home_pub , * home , * local_pos , * global_pos , * attitude ) ;
}
2014-05-11 13:36:51 +02:00
}
}
2013-09-22 14:43:12 +02:00
}
2013-07-31 20:58:27 +04:00
break ;
2013-01-11 07:42:09 +01:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_OVERRIDE_GOTO : {
2014-01-26 11:52:33 +01:00
// TODO listen vehicle_command topic directly from navigator (?)
2014-07-13 11:41:39 +02:00
// Increase by 0.5f and rely on the integer cast
// implicit floor(). This is the *safest* way to
// convert from floats representing small ints to actual ints.
unsigned int mav_goto = ( cmd - > param1 + 0.5f ) ;
2014-01-26 11:52:33 +01:00
2013-12-29 22:38:22 +04:00
if ( mav_goto = = 0 ) { // MAV_GOTO_DO_HOLD
2015-01-28 07:58:42 +01:00
status_local - > nav_state = vehicle_status_s : : NAVIGATION_STATE_AUTO_LOITER ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Pause mission cmd " ) ;
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2013-12-29 22:38:22 +04:00
} else if ( mav_goto = = 1 ) { // MAV_GOTO_DO_CONTINUE
2015-01-28 07:58:42 +01:00
status_local - > nav_state = vehicle_status_s : : NAVIGATION_STATE_AUTO_MISSION ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Continue mission cmd " ) ;
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2013-12-29 22:38:22 +04:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f " ,
2014-10-23 16:17:20 +02:00
( double ) cmd - > param1 ,
( double ) cmd - > param2 ,
( double ) cmd - > param3 ,
( double ) cmd - > param4 ,
( double ) cmd - > param5 ,
( double ) cmd - > param6 ,
( double ) cmd - > param7 ) ;
2013-12-29 22:38:22 +04:00
}
}
break ;
2015-01-16 16:46:16 +01:00
/* Flight termination */
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_DO_FLIGHTTERMINATION : {
2016-02-22 22:15:12 +01:00
if ( cmd - > param1 > 1.5f ) {
armed_local - > lockdown = true ;
warnx ( " forcing lockdown (motors off) " ) ;
} else if ( cmd - > param1 > 0.5f ) {
2014-07-19 14:39:41 +02:00
//XXX update state machine?
armed_local - > force_failsafe = true ;
2014-08-15 00:07:38 +02:00
warnx ( " forcing failsafe (termination) " ) ;
2014-10-23 16:17:20 +02:00
2016-02-23 13:06:41 +01:00
/* param2 is currently used for other failsafe modes */
status_local - > engine_failure_cmd = false ;
2016-02-26 11:01:12 +00:00
status_flags . data_link_lost_cmd = false ;
status_flags . gps_failure_cmd = false ;
status_flags . rc_signal_lost_cmd = false ;
status_flags . vtol_transition_failure_cmd = false ;
2016-02-23 13:06:41 +01:00
if ( ( int ) cmd - > param2 < = 0 ) {
/* reset all commanded failure modes */
warnx ( " reset all non-flighttermination failsafe commands " ) ;
} else if ( ( int ) cmd - > param2 = = 1 ) {
/* trigger engine failure mode */
status_local - > engine_failure_cmd = true ;
warnx ( " engine failure mode commanded " ) ;
} else if ( ( int ) cmd - > param2 = = 2 ) {
/* trigger data link loss mode */
2016-02-26 11:01:12 +00:00
status_flags . data_link_lost_cmd = true ;
2016-02-23 13:06:41 +01:00
warnx ( " data link loss mode commanded " ) ;
} else if ( ( int ) cmd - > param2 = = 3 ) {
/* trigger gps loss mode */
2016-02-26 11:01:12 +00:00
status_flags . gps_failure_cmd = true ;
2016-04-17 19:06:00 +02:00
warnx ( " GPS loss mode commanded " ) ;
2016-02-23 13:06:41 +01:00
} else if ( ( int ) cmd - > param2 = = 4 ) {
/* trigger rc loss mode */
2016-02-26 11:01:12 +00:00
status_flags . rc_signal_lost_cmd = true ;
2016-04-17 19:06:00 +02:00
warnx ( " RC loss mode commanded " ) ;
2016-02-23 13:06:41 +01:00
} else if ( ( int ) cmd - > param2 = = 5 ) {
/* trigger vtol transition failure mode */
2016-02-26 11:01:12 +00:00
status_flags . vtol_transition_failure_cmd = true ;
2016-02-23 13:06:41 +01:00
warnx ( " vtol transition failure mode commanded " ) ;
}
2013-12-08 16:52:41 +01:00
} else {
2014-07-19 14:39:41 +02:00
armed_local - > force_failsafe = false ;
2016-02-22 22:15:12 +01:00
armed_local - > lockdown = false ;
2016-02-23 13:06:41 +01:00
warnx ( " disabling failsafe and lockdown " ) ;
2013-12-08 16:52:41 +01:00
}
2014-10-23 16:17:20 +02:00
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2013-12-08 16:52:41 +01:00
}
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_DO_SET_HOME : {
2014-04-02 16:53:22 +04:00
bool use_current = cmd - > param1 > 0.5f ;
2014-05-11 13:36:51 +02:00
2014-04-02 16:53:22 +04:00
if ( use_current ) {
/* use current position */
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_global_position_valid ) {
2014-04-02 16:53:22 +04:00
home - > lat = global_pos - > lat ;
home - > lon = global_pos - > lon ;
home - > alt = global_pos - > alt ;
home - > timestamp = hrt_absolute_time ( ) ;
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2014-04-02 16:53:22 +04:00
} else {
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2014-04-02 16:53:22 +04:00
}
} else {
/* use specified position */
home - > lat = cmd - > param5 ;
home - > lon = cmd - > param6 ;
home - > alt = cmd - > param7 ;
home - > timestamp = hrt_absolute_time ( ) ;
2015-05-26 22:55:14 -07:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2014-04-02 16:53:22 +04:00
}
2015-05-26 22:55:14 -07:00
if ( cmd_result = = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Home position: %.7f, %.7f, %.2f " , home - > lat , home - > lon , ( double ) home - > alt ) ;
2014-04-02 16:53:22 +04:00
/* announce new home position */
2015-05-25 22:21:23 -07:00
if ( * home_pub ! = nullptr ) {
2014-04-05 16:59:01 +04:00
orb_publish ( ORB_ID ( home_position ) , * home_pub , home ) ;
2014-04-02 16:53:22 +04:00
} else {
2014-04-05 16:59:01 +04:00
* home_pub = orb_advertise ( ORB_ID ( home_position ) , home ) ;
2014-04-02 16:53:22 +04:00
}
/* mark home position as set */
2016-02-25 17:00:39 +00:00
status_flags . condition_home_position_valid = true ;
2014-04-02 16:53:22 +04:00
}
}
break ;
2014-10-23 16:17:20 +02:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_NAV_GUIDED_ENABLE : {
2014-07-14 11:19:06 +02:00
transition_result_t res = TRANSITION_DENIED ;
2016-02-26 15:41:03 +00:00
static main_state_t main_state_pre_offboard = commander_state_s : : MAIN_STATE_MANUAL ;
2014-10-23 16:17:20 +02:00
2016-02-26 15:41:03 +00:00
if ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_OFFBOARD ) {
main_state_pre_offboard = internal_state . main_state ;
2014-07-14 11:19:06 +02:00
}
2014-10-23 16:17:20 +02:00
2014-07-14 11:19:06 +02:00
if ( cmd - > param1 > 0.5f ) {
2016-02-26 15:41:03 +00:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_OFFBOARD , main_state_prev , & status_flags , & internal_state ) ;
2014-10-23 16:17:20 +02:00
2014-07-14 11:19:06 +02:00
if ( res = = TRANSITION_DENIED ) {
print_reject_mode ( status_local , " OFFBOARD " ) ;
2016-02-26 10:20:52 +00:00
status_flags . offboard_control_set_by_command = false ;
2014-10-23 16:17:20 +02:00
2014-07-16 09:38:57 +02:00
} else {
/* Set flag that offboard was set via command, main state is not overridden by rc */
2016-02-26 10:20:52 +00:00
status_flags . offboard_control_set_by_command = true ;
2014-07-14 11:19:06 +02:00
}
2014-10-23 16:17:20 +02:00
2014-07-14 11:19:06 +02:00
} else {
/* If the mavlink command is used to enable or disable offboard control:
* switch back to previous mode when disabling */
2016-02-26 15:41:03 +00:00
res = main_state_transition ( status_local , main_state_pre_offboard , main_state_prev , & status_flags , & internal_state ) ;
2016-02-26 10:20:52 +00:00
status_flags . offboard_control_set_by_command = false ;
2014-07-14 11:19:06 +02:00
}
2016-06-21 16:20:33 +08:00
if ( res = = TRANSITION_DENIED ) {
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
} else {
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
}
2014-07-14 11:19:06 +02:00
}
break ;
2014-10-23 16:17:20 +02:00
2015-11-20 11:15:17 +01:00
case vehicle_command_s : : VEHICLE_CMD_NAV_TAKEOFF : {
/* ok, home set, use it to take off */
2016-02-26 15:41:03 +00:00
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_TAKEOFF , main_state_prev , & status_flags , & internal_state ) ) {
2016-05-13 11:03:18 +02:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Taking off " ) ;
2016-06-21 16:20:33 +08:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2015-11-20 11:15:17 +01:00
} else {
2016-05-13 11:03:18 +02:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " Takeoff denied, disarm and re-try " ) ;
2016-06-21 16:20:33 +08:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2015-11-20 11:15:17 +01:00
}
}
break ;
2015-12-28 16:00:32 +01:00
case vehicle_command_s : : VEHICLE_CMD_NAV_LAND : {
2016-02-26 15:41:03 +00:00
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_LAND , main_state_prev , & status_flags , & internal_state ) ) {
2016-05-13 11:03:18 +02:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Landing at current position " ) ;
2016-06-21 16:20:33 +08:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
2015-12-28 16:00:32 +01:00
} else {
2016-05-13 11:03:18 +02:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " Landing denied, land manually. " ) ;
2016-06-21 16:20:33 +08:00
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED ;
2015-12-28 16:00:32 +01:00
}
}
break ;
2016-05-19 23:46:06 +02:00
case vehicle_command_s : : VEHICLE_CMD_NAV_ROI :
case vehicle_command_s : : VEHICLE_CMD_DO_SET_ROI : {
roi - > mode = cmd - > param1 ;
if ( roi - > mode = = vehicle_roi_s : : VEHICLE_ROI_WPINDEX ) {
roi - > mission_seq = cmd - > param2 ;
}
else if ( roi - > mode = = vehicle_roi_s : : VEHICLE_ROI_LOCATION ) {
roi - > lat = cmd - > param5 ;
roi - > lon = cmd - > param6 ;
roi - > alt = cmd - > param7 ;
}
else if ( roi - > mode = = vehicle_roi_s : : VEHICLE_ROI_TARGET ) {
roi - > target_seq = cmd - > param2 ;
}
if ( * roi_pub ! = nullptr ) {
orb_publish ( ORB_ID ( vehicle_roi ) , * roi_pub , roi ) ;
} else {
* roi_pub = orb_advertise ( ORB_ID ( vehicle_roi ) , roi ) ;
}
cmd_result = vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED ;
break ;
}
2016-07-04 14:17:27 -04:00
case vehicle_command_s : : VEHICLE_CMD_CUSTOM_0 :
case vehicle_command_s : : VEHICLE_CMD_CUSTOM_1 :
case vehicle_command_s : : VEHICLE_CMD_CUSTOM_2 :
2016-05-19 23:46:06 +02:00
case vehicle_command_s : : VEHICLE_CMD_DO_MOUNT_CONTROL :
case vehicle_command_s : : VEHICLE_CMD_DO_MOUNT_CONFIGURE :
case vehicle_command_s : : VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT :
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN :
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_CALIBRATION :
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS :
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_STORAGE :
2015-08-23 13:50:59 +02:00
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_UAVCAN :
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY :
case vehicle_command_s : : VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY :
2015-06-16 15:47:55 +05:30
case vehicle_command_s : : VEHICLE_CMD_DO_TRIGGER_CONTROL :
2015-08-06 00:02:54 +02:00
case vehicle_command_s : : VEHICLE_CMD_DO_VTOL_TRANSITION :
2016-02-23 09:25:29 +01:00
case vehicle_command_s : : VEHICLE_CMD_DO_DIGICAM_CONTROL :
case vehicle_command_s : : VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST :
2016-02-17 16:50:13 +01:00
case vehicle_command_s : : VEHICLE_CMD_DO_CHANGE_SPEED :
2016-08-29 23:35:56 +02:00
case vehicle_command_s : : VEHICLE_CMD_DO_GO_AROUND :
2016-06-21 13:36:35 +02:00
case vehicle_command_s : : VEHICLE_CMD_START_RX_PAIR :
2013-12-29 12:16:49 +04:00
/* ignore commands that handled in low prio loop */
break ;
2013-05-17 11:24:02 +02:00
default :
2014-04-07 21:42:19 +02:00
/* Warn about unsupported commands, this makes sense because only commands
* to this component ID ( or all ) are passed by mavlink . */
2015-12-12 13:01:49 +01:00
answer_command ( * cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_UNSUPPORTED , * command_ack_pub , * command_ack ) ;
2012-08-04 15:12:36 -07:00
break ;
}
2014-05-11 13:36:51 +02:00
2015-05-26 22:55:14 -07:00
if ( cmd_result ! = vehicle_command_s : : VEHICLE_CMD_RESULT_UNSUPPORTED ) {
2014-04-07 21:42:19 +02:00
/* already warned about unsupported commands in "default" case */
2015-12-12 13:01:49 +01:00
answer_command ( * cmd , cmd_result , * command_ack_pub , * command_ack ) ;
2012-08-04 15:12:36 -07:00
}
2014-06-29 13:55:55 -07:00
return true ;
2012-08-04 15:12:36 -07:00
}
2015-01-16 16:43:11 +01:00
/**
* @ brief This function initializes the home position of the vehicle . This happens first time we get a good GPS fix and each
* time the vehicle is armed with a good GPS fix .
* */
2015-01-16 16:46:16 +01:00
static void commander_set_home_position ( orb_advert_t & homePub , home_position_s & home ,
2015-10-27 09:58:54 +01:00
const vehicle_local_position_s & localPosition , const vehicle_global_position_s & globalPosition ,
const vehicle_attitude_s & attitude )
2015-01-16 16:43:11 +01:00
{
//Need global position fix to be able to set home
2016-02-25 17:00:39 +00:00
if ( ! status_flags . condition_global_position_valid ) {
2015-01-16 16:43:11 +01:00
return ;
}
//Ensure that the GPS accuracy is good enough for intializing home
2015-01-16 16:46:16 +01:00
if ( globalPosition . eph > eph_threshold | | globalPosition . epv > epv_threshold ) {
2015-01-16 16:43:11 +01:00
return ;
}
//Set home position
home . timestamp = hrt_absolute_time ( ) ;
home . lat = globalPosition . lat ;
home . lon = globalPosition . lon ;
home . alt = globalPosition . alt ;
home . x = localPosition . x ;
home . y = localPosition . y ;
home . z = localPosition . z ;
2015-10-27 09:58:54 +01:00
home . yaw = attitude . yaw ;
2016-02-09 21:45:56 +01:00
PX4_INFO ( " home: %.7f, %.7f, %.2f " , home . lat , home . lon , ( double ) home . alt ) ;
2015-01-16 16:43:11 +01:00
/* announce new home position */
2015-05-25 22:21:23 -07:00
if ( homePub ! = nullptr ) {
2015-01-16 16:43:11 +01:00
orb_publish ( ORB_ID ( home_position ) , homePub , & home ) ;
} else {
homePub = orb_advertise ( ORB_ID ( home_position ) , & home ) ;
}
//Play tune first time we initialize HOME
2016-02-25 17:00:39 +00:00
if ( ! status_flags . condition_home_position_valid ) {
2015-06-13 18:37:19 +02:00
tune_home_set ( true ) ;
2015-01-16 16:43:11 +01:00
}
/* mark home position as set */
2016-02-25 17:00:39 +00:00
status_flags . condition_home_position_valid = true ;
2015-01-16 16:43:11 +01: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 ;
2015-11-10 19:33:14 +05:30
bool sensor_fail_tune_played = false ;
2013-06-25 13:15:38 +02:00
bool arm_tune_played = false ;
2015-10-24 19:14:23 +02:00
bool was_landed = true ;
2016-01-28 13:26:49 +01:00
bool was_falling = false ;
2014-04-02 11:57:41 +04:00
bool was_armed = false ;
2013-06-25 13:15:38 +02:00
2015-08-25 21:59:01 -07:00
bool startup_in_hil = false ;
2015-08-26 16:17:07 +02:00
2016-02-25 17:00:39 +00:00
// XXX for now just set sensors as initialized
status_flags . condition_system_sensors_initialized = true ;
2015-08-26 16:17:07 +02:00
# ifdef __PX4_NUTTX
/* NuttX indicates 3 arguments when only 2 are present */
argc - = 1 ;
2016-05-25 20:56:25 +02:00
argv + = 1 ;
2015-08-26 16:17:07 +02:00
# endif
if ( argc > 2 ) {
2016-05-05 19:51:13 -07:00
if ( ! strcmp ( argv [ 2 ] , " -hil " ) ) {
2015-08-25 21:59:01 -07:00
startup_in_hil = true ;
} else {
2016-06-01 15:45:19 +01:00
PX4_ERR ( " Argument %s not supported, abort. " , argv [ 2 ] ) ;
2015-08-25 21:59:01 -07:00
thread_should_exit = true ;
}
}
2012-09-21 12:55:41 +02:00
/* set parameters */
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 " ) ;
2016-04-23 16:51:10 +02:00
param_t _param_enable_datalink_loss = param_find ( " NAV_DLL_ACT " ) ;
2016-06-20 19:23:11 +02:00
param_t _param_offboard_loss_act = param_find ( " COM_OBL_ACT " ) ;
param_t _param_offboard_loss_rc_act = param_find ( " COM_OBL_RC_ACT " ) ;
2016-06-06 11:19:10 +02:00
param_t _param_enable_rc_loss = param_find ( " NAV_RCL_ACT " ) ;
2014-07-20 17:53:04 +02:00
param_t _param_datalink_loss_timeout = param_find ( " COM_DL_LOSS_T " ) ;
2014-09-05 12:06:05 +02:00
param_t _param_rc_loss_timeout = param_find ( " COM_RC_LOSS_T " ) ;
2014-07-24 08:57:58 +02:00
param_t _param_datalink_regain_timeout = param_find ( " COM_DL_REG_T " ) ;
2014-09-05 08:59:00 +02:00
param_t _param_ef_throttle_thres = param_find ( " COM_EF_THROT " ) ;
param_t _param_ef_current2throttle_thres = param_find ( " COM_EF_C2T " ) ;
param_t _param_ef_time_thres = param_find ( " COM_EF_TIME " ) ;
2014-12-02 10:47:07 +01:00
param_t _param_autostart_id = param_find ( " SYS_AUTOSTART " ) ;
2015-04-03 18:50:44 +02:00
param_t _param_autosave_params = param_find ( " COM_AUTOS_PAR " ) ;
2015-05-24 17:40:06 +02:00
param_t _param_rc_in_off = param_find ( " COM_RC_IN_MODE " ) ;
2016-05-20 09:59:23 -06:00
param_t _param_rc_arm_hyst = param_find ( " COM_RC_ARM_HYST " ) ;
2015-07-10 09:50:56 +02:00
param_t _param_eph = param_find ( " COM_HOME_H_T " ) ;
param_t _param_epv = param_find ( " COM_HOME_V_T " ) ;
2015-09-27 19:49:01 -04:00
param_t _param_geofence_action = param_find ( " GF_ACTION " ) ;
2015-10-26 09:22:34 +01:00
param_t _param_disarm_land = param_find ( " COM_DISARM_LAND " ) ;
2016-04-23 00:30:50 +02:00
param_t _param_low_bat_act = param_find ( " COM_LOW_BAT_ACT " ) ;
2015-11-26 17:45:20 +01:00
param_t _param_offboard_loss_timeout = param_find ( " COM_OF_LOSS_T " ) ;
2016-06-06 11:18:26 +02:00
param_t _param_arm_without_gps = param_find ( " COM_ARM_WO_GPS " ) ;
2012-12-13 10:23:02 +01:00
2016-03-04 11:47:33 +01:00
param_t _param_fmode_1 = param_find ( " COM_FLTMODE1 " ) ;
param_t _param_fmode_2 = param_find ( " COM_FLTMODE2 " ) ;
param_t _param_fmode_3 = param_find ( " COM_FLTMODE3 " ) ;
param_t _param_fmode_4 = param_find ( " COM_FLTMODE4 " ) ;
param_t _param_fmode_5 = param_find ( " COM_FLTMODE5 " ) ;
param_t _param_fmode_6 = param_find ( " COM_FLTMODE6 " ) ;
2015-11-22 12:43:58 +01:00
// These are too verbose, but we will retain them a little longer
// until we are sure we really don't need them.
2016-02-26 15:41:03 +00:00
// const char *main_states_str[commander_state_s::MAIN_STATE_MAX];
// main_states_str[commander_state_s::MAIN_STATE_MANUAL] = "MANUAL";
// main_states_str[commander_state_s::MAIN_STATE_ALTCTL] = "ALTCTL";
// main_states_str[commander_state_s::MAIN_STATE_POSCTL] = "POSCTL";
// main_states_str[commander_state_s::MAIN_STATE_AUTO_MISSION] = "AUTO_MISSION";
// main_states_str[commander_state_s::MAIN_STATE_AUTO_LOITER] = "AUTO_LOITER";
// main_states_str[commander_state_s::MAIN_STATE_AUTO_RTL] = "AUTO_RTL";
// main_states_str[commander_state_s::MAIN_STATE_ACRO] = "ACRO";
// main_states_str[commander_state_s::MAIN_STATE_STAB] = "STAB";
// main_states_str[commander_state_s::MAIN_STATE_OFFBOARD] = "OFFBOARD";
2015-01-28 07:58:42 +01:00
2015-11-22 12:43:58 +01:00
// const char *nav_states_str[vehicle_status_s::NAVIGATION_STATE_MAX];
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_MANUAL] = "MANUAL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_STAB] = "STAB";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_RATTITUDE] = "RATTITUDE";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_ALTCTL] = "ALTCTL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_POSCTL] = "POSCTL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION] = "AUTO_MISSION";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER] = "AUTO_LOITER";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_RTL] = "AUTO_RTL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF] = "AUTO_TAKEOFF";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER] = "AUTO_RCRECOVER";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS] = "AUTO_RTGS";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL] = "AUTO_LANDENGFAIL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL] = "AUTO_LANDGPSFAIL";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_ACRO] = "ACRO";
2016-03-13 15:39:35 +01:00
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_AUTO_LAND] = "LAND";
2015-11-22 12:43:58 +01:00
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_DESCEND] = "DESCEND";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_TERMINATION] = "TERMINATION";
// nav_states_str[vehicle_status_s::NAVIGATION_STATE_OFFBOARD] = "OFFBOARD";
2014-01-25 23:37:26 +01: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 */
2015-03-28 13:54:05 -07:00
if ( led_init ( ) ! = OK ) {
2016-04-21 16:56:37 +02:00
PX4_WARN ( " LED init failed " ) ;
2012-08-04 15:12:36 -07:00
}
2013-06-25 16:30:35 +02:00
if ( buzzer_init ( ) ! = OK ) {
2016-04-21 16:56:37 +02:00
PX4_WARN ( " Buzzer init failed " ) ;
2015-03-28 13:54:05 -07:00
}
2014-01-27 20:49:17 +01:00
/* vehicle status topic */
2013-07-28 23:12:16 +04:00
memset ( & status , 0 , sizeof ( status ) ) ;
2016-02-25 17:00:39 +00:00
2014-02-01 13:21:51 +01:00
// We want to accept RC inputs as default
2016-02-26 11:01:12 +00:00
status_flags . rc_input_blocked = false ;
2015-05-25 16:34:42 +02:00
status . rc_input_mode = vehicle_status_s : : RC_IN_MODE_DEFAULT ;
2016-04-22 15:15:37 -04:00
internal_state . main_state = commander_state_s : : MAIN_STATE_MANUAL ;
2016-07-19 09:21:35 +02:00
internal_state . timestamp = hrt_absolute_time ( ) ;
2016-02-26 15:41:03 +00:00
main_state_prev = commander_state_s : : MAIN_STATE_MAX ;
2015-01-28 07:58:42 +01:00
status . nav_state = vehicle_status_s : : NAVIGATION_STATE_MANUAL ;
status . arming_state = vehicle_status_s : : ARMING_STATE_INIT ;
2015-08-25 21:59:01 -07:00
2016-05-25 20:56:25 +02:00
if ( startup_in_hil ) {
2015-08-25 21:59:01 -07:00
status . hil_state = vehicle_status_s : : HIL_STATE_ON ;
} else {
status . hil_state = vehicle_status_s : : HIL_STATE_OFF ;
}
2014-06-16 17:34:21 +02:00
status . failsafe = false ;
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 */
2016-02-26 10:20:52 +00:00
status_flags . offboard_control_signal_found_once = false ;
2016-02-26 11:01:12 +00:00
status_flags . 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 ;
2016-02-26 10:20:52 +00:00
status_flags . offboard_control_signal_lost = true ;
2014-06-16 17:34:21 +02:00
status . data_link_lost = true ;
2015-11-26 17:45:20 +01:00
status_flags . offboard_control_loss_timeout = false ;
2013-02-16 13:40:09 -08:00
2016-02-25 17:00:39 +00:00
status_flags . condition_system_prearm_error_reported = false ;
status_flags . condition_system_hotplug_timeout = false ;
2013-02-17 23:07:07 -08:00
2013-07-28 23:12:16 +04:00
status . timestamp = hrt_absolute_time ( ) ;
2014-01-27 20:49:17 +01:00
2016-02-25 17:00:39 +00:00
status_flags . condition_power_input_valid = true ;
2016-02-26 11:01:12 +00:00
avionics_power_rail_voltage = - 1.0f ;
2016-02-25 17:00:39 +00:00
status_flags . usb_connected = false ;
2014-05-25 08:22:54 +02:00
2014-05-25 20:34:32 +02:00
// CIRCUIT BREAKERS
2016-02-25 17:00:39 +00:00
status_flags . circuit_breaker_engaged_power_check = false ;
status_flags . circuit_breaker_engaged_airspd_check = false ;
status_flags . circuit_breaker_engaged_enginefailure_check = false ;
status_flags . circuit_breaker_engaged_gpsfailure_check = false ;
2015-05-14 19:19:30 +02:00
get_circuit_breaker_params ( ) ;
2014-05-25 20:34:32 +02:00
2014-01-27 20:49:17 +01:00
/* publish initial state */
status_pub = orb_advertise ( ORB_ID ( vehicle_status ) , & status ) ;
2014-10-23 16:17:20 +02:00
2015-05-25 22:21:23 -07:00
if ( status_pub = = nullptr ) {
2014-06-13 23:40:48 +02:00
warnx ( " ERROR: orb_advertise for topic vehicle_status failed (uorb app running?). \n " ) ;
warnx ( " exiting. " ) ;
2015-04-15 19:38:59 -07:00
px4_task_exit ( ERROR ) ;
2014-06-13 23:40:48 +02:00
}
2014-01-27 20:49:17 +01:00
/* Initialize armed with all false */
memset ( & armed , 0 , sizeof ( armed ) ) ;
2015-10-24 19:14:23 +02:00
/* armed topic */
orb_advert_t armed_pub = orb_advertise ( ORB_ID ( actuator_armed ) , & armed ) ;
2014-01-27 20:49:17 +01:00
/* vehicle control mode topic */
memset ( & control_mode , 0 , sizeof ( control_mode ) ) ;
orb_advert_t control_mode_pub = orb_advertise ( ORB_ID ( vehicle_control_mode ) , & control_mode ) ;
2013-06-25 16:30:35 +02:00
2013-01-19 14:46:26 +01:00
/* home position */
2015-05-25 22:21:23 -07:00
orb_advert_t home_pub = nullptr ;
2015-06-08 15:19:41 +02:00
memset ( & _home , 0 , sizeof ( _home ) ) ;
2013-01-19 14:46:26 +01:00
2016-05-19 23:46:06 +02:00
/* region of interest */
orb_advert_t roi_pub = nullptr ;
memset ( & _roi , 0 , sizeof ( _roi ) ) ;
2015-12-12 13:01:49 +01:00
/* command ack */
orb_advert_t command_ack_pub = nullptr ;
struct vehicle_command_ack_s command_ack ;
memset ( & command_ack , 0 , sizeof ( command_ack ) ) ;
2014-06-14 23:57:29 +02:00
/* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */
2015-05-25 22:21:23 -07:00
orb_advert_t mission_pub = nullptr ;
2014-06-13 23:40:48 +02:00
mission_s mission ;
2014-10-23 16:17:20 +02:00
2016-02-29 09:40:11 +00:00
orb_advert_t commander_state_pub = nullptr ;
2014-06-13 23:40:48 +02:00
if ( dm_read ( DM_KEY_MISSION_STATE , 0 , & mission , sizeof ( mission_s ) ) = = sizeof ( mission_s ) ) {
if ( mission . dataman_id > = 0 & & mission . dataman_id < = 1 ) {
2015-04-25 09:03:48 +02:00
if ( mission . count > 0 ) {
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " [cmd] Mission #%d loaded, %u WPs, curr: %d " ,
2015-04-25 09:03:48 +02:00
mission . dataman_id , mission . count , mission . current_seq ) ;
}
2014-10-23 16:17:20 +02:00
2014-06-13 23:40:48 +02:00
} else {
2014-07-13 11:43:56 +02:00
const char * missionfail = " reading mission state failed " ;
warnx ( " %s " , missionfail ) ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , missionfail ) ;
2014-06-14 23:57:29 +02:00
/* initialize mission state in dataman */
mission . dataman_id = 0 ;
mission . count = 0 ;
mission . current_seq = 0 ;
dm_write ( DM_KEY_MISSION_STATE , 0 , DM_PERSIST_POWER_ON_RESET , & mission , sizeof ( mission_s ) ) ;
2014-06-13 23:40:48 +02:00
}
2012-08-04 15:12:36 -07:00
2014-06-14 23:57:29 +02:00
mission_pub = orb_advertise ( ORB_ID ( offboard_mission ) , & mission ) ;
orb_publish ( ORB_ID ( offboard_mission ) , mission_pub , & mission ) ;
2012-08-04 15:12:36 -07:00
}
2013-09-08 20:05:15 +02:00
int ret ;
2012-08-04 15:12:36 -07:00
/* Start monitoring loop */
2013-07-16 18:55:32 +02:00
unsigned counter = 0 ;
unsigned stick_off_counter = 0 ;
unsigned stick_on_counter = 0 ;
2012-08-04 15:12:36 -07: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-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 ) ) ;
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
2014-05-27 21:56:32 +02:00
/* Subscribe to mission result topic */
int mission_result_sub = orb_subscribe ( ORB_ID ( mission_result ) ) ;
struct mission_result_s mission_result ;
memset ( & mission_result , 0 , sizeof ( mission_result ) ) ;
2014-12-19 22:26:31 +00:00
/* Subscribe to geofence result topic */
int geofence_result_sub = orb_subscribe ( ORB_ID ( geofence_result ) ) ;
struct geofence_result_s geofence_result ;
memset ( & geofence_result , 0 , sizeof ( geofence_result ) ) ;
2012-09-21 12:55:41 +02:00
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe ( ORB_ID ( manual_control_setpoint ) ) ;
memset ( & sp_man , 0 , sizeof ( sp_man ) ) ;
/* Subscribe to offboard control data */
2015-02-13 23:19:43 +01:00
int offboard_control_mode_sub = orb_subscribe ( ORB_ID ( offboard_control_mode ) ) ;
memset ( & offboard_control_mode , 0 , sizeof ( offboard_control_mode ) ) ;
2012-08-04 15:12:36 -07:00
2014-07-06 16:08:37 +02:00
/* Subscribe to telemetry status topics */
2015-07-12 12:34:48 +02:00
int telemetry_subs [ ORB_MULTI_MAX_INSTANCES ] ;
uint64_t telemetry_last_heartbeat [ ORB_MULTI_MAX_INSTANCES ] ;
uint64_t telemetry_last_dl_loss [ ORB_MULTI_MAX_INSTANCES ] ;
bool telemetry_lost [ ORB_MULTI_MAX_INSTANCES ] ;
2014-07-06 16:08:37 +02:00
2015-07-12 12:34:48 +02:00
for ( int i = 0 ; i < ORB_MULTI_MAX_INSTANCES ; i + + ) {
2015-04-25 07:08:44 +02:00
telemetry_subs [ i ] = - 1 ;
2014-07-06 16:08:37 +02:00
telemetry_last_heartbeat [ i ] = 0 ;
2014-07-24 08:57:58 +02:00
telemetry_last_dl_loss [ i ] = 0 ;
2014-07-06 16:08:37 +02:00
telemetry_lost [ i ] = true ;
}
2014-06-16 17:34:21 +02: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 ) ) ;
2014-05-07 08:42:57 +02:00
/* Init EPH and EPV */
global_position . eph = 1000.0f ;
global_position . epv = 1000.0f ;
2012-12-13 10:23:02 +01:00
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 ) ) ;
2015-10-27 09:58:54 +01:00
struct vehicle_local_position_s local_position = { } ;
/* Subscribe to attitude data */
int attitude_sub = orb_subscribe ( ORB_ID ( vehicle_attitude ) ) ;
struct vehicle_attitude_s attitude = { } ;
2012-08-04 15:12:36 -07:00
2015-01-06 12:25:18 +01:00
/* Subscribe to land detector */
int land_detector_sub = orb_subscribe ( ORB_ID ( vehicle_land_detected ) ) ;
2015-10-27 09:58:54 +01:00
struct vehicle_land_detected_s land_detector = { } ;
2016-04-29 12:34:28 +02:00
land_detector . landed = true ;
2015-01-06 12:25:18 +01: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 ) ) ;
2014-07-01 09:51:35 +02:00
gps_position . eph = FLT_MAX ;
gps_position . epv = FLT_MAX ;
2013-01-19 14:46:26 +01:00
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 ) ) ;
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 ) ) ;
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 ) ) ;
memset ( & battery , 0 , sizeof ( battery ) ) ;
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 ) ) ;
2014-04-03 20:23:34 +04:00
/* Subscribe to position setpoint triplet */
int pos_sp_triplet_sub = orb_subscribe ( ORB_ID ( position_setpoint_triplet ) ) ;
struct position_setpoint_triplet_s pos_sp_triplet ;
memset ( & pos_sp_triplet , 0 , sizeof ( pos_sp_triplet ) ) ;
2014-05-25 08:22:54 +02:00
/* Subscribe to system power */
int system_power_sub = orb_subscribe ( ORB_ID ( system_power ) ) ;
struct system_power_s system_power ;
memset ( & system_power , 0 , sizeof ( system_power ) ) ;
2014-07-19 14:12:33 +02:00
/* Subscribe to actuator controls (outputs) */
int actuator_controls_sub = orb_subscribe ( ORB_ID_VEHICLE_ATTITUDE_CONTROLS ) ;
struct actuator_controls_s actuator_controls ;
memset ( & actuator_controls , 0 , sizeof ( actuator_controls ) ) ;
2014-12-02 10:47:07 +01:00
/* Subscribe to vtol vehicle status topic */
int vtol_vehicle_status_sub = orb_subscribe ( ORB_ID ( vtol_vehicle_status ) ) ;
2015-08-07 16:43:16 +02:00
//struct vtol_vehicle_status_s vtol_status;
2014-12-02 10:47:07 +01:00
memset ( & vtol_status , 0 , sizeof ( vtol_status ) ) ;
vtol_status . vtol_in_rw_mode = true ; //default for vtol is rotary wing
2016-02-26 18:14:03 -08:00
int cpuload_sub = orb_subscribe ( ORB_ID ( cpuload ) ) ;
memset ( & cpuload , 0 , sizeof ( cpuload ) ) ;
2014-12-02 10:47:07 +01:00
2016-02-26 18:14:03 -08:00
control_status_leds ( & status , & armed , true , & battery , & cpuload ) ;
2013-08-29 16:45:33 +02:00
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
2015-04-22 09:53:09 +02:00
/* update vehicle status to find out vehicle type (required for preflight checks) */
param_get ( _param_sys_type , & ( status . system_type ) ) ; // get system type
status . is_rotary_wing = is_rotary_wing ( & status ) | | is_vtol ( & status ) ;
2015-04-19 23:07:32 +02:00
bool checkAirspeed = false ;
/* Perform airspeed check only if circuit breaker is not
* engaged and it ' s not a rotary wing */
2016-02-25 17:00:39 +00:00
if ( ! status_flags . circuit_breaker_engaged_airspd_check & & ! status . is_rotary_wing ) {
2015-04-19 23:07:32 +02:00
checkAirspeed = true ;
}
2015-04-27 13:29:36 +02:00
// Run preflight check
2015-09-04 19:57:44 +02:00
int32_t rc_in_off = 0 ;
2015-11-10 19:33:14 +05:30
bool hotplug_timeout = hrt_elapsed_time ( & commander_boot_timestamp ) > HOTPLUG_SENS_TIMEOUT ;
2016-06-06 11:18:26 +02:00
int32_t arm_without_gps = 0 ;
2015-06-05 21:18:25 -06:00
param_get ( _param_autostart_id , & autostart_id ) ;
2015-10-06 11:48:35 +02:00
param_get ( _param_rc_in_off , & rc_in_off ) ;
2016-06-06 11:18:26 +02:00
param_get ( _param_arm_without_gps , & arm_without_gps ) ;
2016-06-07 16:00:23 +02:00
can_arm_without_gps = ( arm_without_gps = = 1 ) ;
2015-10-06 11:48:35 +02:00
status . rc_input_mode = rc_in_off ;
2015-06-10 11:05:56 -06:00
if ( is_hil_setup ( autostart_id ) ) {
2015-06-06 15:03:03 -06:00
// HIL configuration selected: real sensors will be disabled
2016-02-25 17:00:39 +00:00
status_flags . condition_system_sensors_initialized = false ;
2015-03-08 14:50:35 +01:00
set_tune_override ( TONE_STARTUP_TUNE ) ; //normal boot tune
2015-06-06 15:03:03 -06:00
} else {
2016-05-20 09:59:23 -06:00
// sensor diagnostics done continuously, not just at boot so don't warn about any issues just yet
2016-02-25 17:00:39 +00:00
status_flags . condition_system_sensors_initialized = Commander : : preflightCheck ( & mavlink_log_pub , true , true , true , true ,
checkAirspeed , ( status . rc_input_mode = = vehicle_status_s : : RC_IN_MODE_DEFAULT ) ,
2016-07-12 12:12:59 +02:00
! can_arm_without_gps , /*checkDynamic */ false , /* reportFailures */ false ) ;
2015-06-05 21:18:25 -06:00
set_tune_override ( TONE_STARTUP_TUNE ) ; //normal boot tune
2015-03-08 14:50:35 +01:00
}
2016-05-20 09:59:23 -06:00
// user adjustable duration required to assert arm/disarm via throttle/rudder stick
int32_t rc_arm_hyst = 100 ;
param_get ( _param_rc_arm_hyst , & rc_arm_hyst ) ;
rc_arm_hyst * = COMMANDER_MONITORING_LOOPSPERMSEC ;
2015-06-08 17:18:25 +02:00
commander_boot_timestamp = hrt_absolute_time ( ) ;
2012-12-23 17:20:53 -08:00
2014-05-27 21:56:32 +02:00
transition_result_t arming_ret ;
2016-04-23 16:51:10 +02:00
int32_t datalink_loss_enabled = 0 ;
2016-06-06 11:19:10 +02:00
int32_t rc_loss_enabled = 0 ;
2014-07-20 17:53:04 +02:00
int32_t datalink_loss_timeout = 10 ;
2014-09-05 12:06:05 +02:00
float rc_loss_timeout = 0.5 ;
2014-07-24 08:57:58 +02:00
int32_t datalink_regain_timeout = 0 ;
2015-11-26 17:45:20 +01:00
float offboard_loss_timeout = 0.0f ;
int32_t offboard_loss_act = 0 ;
int32_t offboard_loss_rc_act = 0 ;
2014-09-05 08:59:00 +02:00
2015-11-02 11:51:50 +01:00
int32_t geofence_action = 0 ;
2015-09-27 19:49:01 -04:00
2014-09-05 08:59:00 +02:00
/* Thresholds for engine failure detection */
int32_t ef_throttle_thres = 1.0f ;
int32_t ef_current2throttle_thres = 0.0f ;
int32_t ef_time_thres = 1000.0f ;
2014-09-30 13:40:03 +02:00
uint64_t timestamp_engine_healthy = 0 ; /**< absolute time when engine was healty */
2014-06-18 19:01:41 +02:00
2015-04-03 18:50:44 +02:00
int autosave_params ; /**< Autosave of parameters enabled/disabled, loaded from parameter */
2015-10-26 09:22:34 +01:00
int32_t disarm_when_landed = 0 ;
2016-04-23 00:30:50 +02:00
int32_t low_bat_action = 0 ;
2015-10-26 09:22:34 +01:00
2014-05-27 21:56:32 +02:00
/* check which state machines for changes, clear "changed" flag */
bool arming_state_changed = false ;
bool main_state_changed = false ;
2014-06-17 13:19:50 +02:00
bool failsafe_old = false ;
2014-05-27 21:56:32 +02:00
2015-03-15 14:33:22 +01:00
/* initialize low priority thread */
pthread_attr_t commander_low_prio_attr ;
pthread_attr_init ( & commander_low_prio_attr ) ;
2016-04-01 15:12:08 +02:00
pthread_attr_setstacksize ( & commander_low_prio_attr , 3000 ) ;
2015-03-15 14:33:22 +01:00
2016-01-18 23:16:31 -08:00
# ifndef __PX4_QURT
2016-02-16 21:11:03 +01:00
// This is not supported by QURT (yet).
2015-03-15 14:33:22 +01:00
struct sched_param param ;
( void ) pthread_attr_getschedparam ( & commander_low_prio_attr , & param ) ;
/* low priority */
param . sched_priority = SCHED_PRIORITY_DEFAULT - 50 ;
( void ) pthread_attr_setschedparam ( & commander_low_prio_attr , & param ) ;
2016-01-18 23:16:31 -08:00
# endif
2015-03-15 14:33:22 +01:00
pthread_create ( & commander_low_prio_thread , & commander_low_prio_attr , commander_low_prio_loop , NULL ) ;
pthread_attr_destroy ( & commander_low_prio_attr ) ;
2012-08-24 00:01:23 +02:00
while ( ! thread_should_exit ) {
2012-08-04 15:12:36 -07:00
2014-05-27 21:56:32 +02:00
arming_ret = TRANSITION_NOT_CHANGED ;
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 ;
2015-03-23 10:52:32 -07:00
2013-06-09 14:09:09 +02:00
/* parameters changed */
2015-03-23 10:52:32 -07:00
struct parameter_update_s param_changed ;
2013-06-09 14:09:09 +02:00
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 */
2015-04-22 09:53:09 +02:00
if ( is_rotary_wing ( & status ) | | ( is_vtol ( & status ) & & vtol_status . vtol_in_rw_mode ) ) {
2013-07-28 23:12:16 +04:00
status . is_rotary_wing = true ;
2013-06-09 14:09:09 +02:00
} else {
2013-07-28 23:12:16 +04:00
status . is_rotary_wing = false ;
2013-06-09 14:09:09 +02:00
}
2014-12-18 14:46:31 +01:00
/* set vehicle_status.is_vtol flag */
2015-04-22 09:53:09 +02:00
status . is_vtol = is_vtol ( & status ) ;
2014-12-18 14:46:31 +01:00
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 ) ) ;
2014-05-25 20:34:32 +02:00
2015-04-27 13:29:36 +02:00
get_circuit_breaker_params ( ) ;
2014-05-25 20:34:32 +02:00
2013-07-31 20:58:27 +04:00
status_changed = true ;
2013-06-09 14:09:09 +02:00
}
2014-05-11 13:36:51 +02:00
2014-12-18 14:46:31 +01:00
/* Safety parameters */
2014-06-18 19:01:41 +02:00
param_get ( _param_enable_datalink_loss , & datalink_loss_enabled ) ;
2016-06-06 11:19:10 +02:00
param_get ( _param_enable_rc_loss , & rc_loss_enabled ) ;
2014-07-20 17:53:04 +02:00
param_get ( _param_datalink_loss_timeout , & datalink_loss_timeout ) ;
2014-09-05 12:06:05 +02:00
param_get ( _param_rc_loss_timeout , & rc_loss_timeout ) ;
2015-05-24 13:15:28 +02:00
param_get ( _param_rc_in_off , & rc_in_off ) ;
2015-05-25 16:34:42 +02:00
status . rc_input_mode = rc_in_off ;
2016-05-20 09:59:23 -06:00
param_get ( _param_rc_arm_hyst , & rc_arm_hyst ) ;
rc_arm_hyst * = COMMANDER_MONITORING_LOOPSPERMSEC ;
2014-07-24 08:57:58 +02:00
param_get ( _param_datalink_regain_timeout , & datalink_regain_timeout ) ;
2014-09-05 08:59:00 +02:00
param_get ( _param_ef_throttle_thres , & ef_throttle_thres ) ;
param_get ( _param_ef_current2throttle_thres , & ef_current2throttle_thres ) ;
param_get ( _param_ef_time_thres , & ef_time_thres ) ;
2015-09-27 19:49:01 -04:00
param_get ( _param_geofence_action , & geofence_action ) ;
2015-10-26 09:22:34 +01:00
param_get ( _param_disarm_land , & disarm_when_landed ) ;
2016-07-17 17:00:59 +01:00
auto_disarm_hysteresis . set_hysteresis_time_from ( false ,
( hrt_abstime ) disarm_when_landed * 1000000 ) ;
2016-04-23 00:30:50 +02:00
param_get ( _param_low_bat_act , & low_bat_action ) ;
2015-11-26 17:45:20 +01:00
param_get ( _param_offboard_loss_timeout , & offboard_loss_timeout ) ;
2016-06-08 13:21:17 +02:00
param_get ( _param_offboard_loss_act , & offboard_loss_act ) ;
param_get ( _param_offboard_loss_rc_act , & offboard_loss_rc_act ) ;
2016-06-06 11:18:26 +02:00
param_get ( _param_arm_without_gps , & arm_without_gps ) ;
2016-06-07 16:00:23 +02:00
can_arm_without_gps = ( arm_without_gps = = 1 ) ;
2014-12-18 14:46:31 +01:00
/* Autostart id */
2014-12-02 10:47:07 +01:00
param_get ( _param_autostart_id , & autostart_id ) ;
2015-04-03 18:50:44 +02:00
/* Parameter autosave setting */
param_get ( _param_autosave_params , & autosave_params ) ;
2015-07-10 09:50:56 +02:00
/* EPH / EPV */
param_get ( _param_eph , & eph_threshold ) ;
param_get ( _param_epv , & epv_threshold ) ;
2015-04-03 18:50:44 +02:00
2016-03-04 11:47:33 +01:00
/* flight mode slots */
param_get ( _param_fmode_1 , & _flight_mode_slots [ 0 ] ) ;
param_get ( _param_fmode_2 , & _flight_mode_slots [ 1 ] ) ;
param_get ( _param_fmode_3 , & _flight_mode_slots [ 2 ] ) ;
param_get ( _param_fmode_4 , & _flight_mode_slots [ 3 ] ) ;
param_get ( _param_fmode_5 , & _flight_mode_slots [ 4 ] ) ;
param_get ( _param_fmode_6 , & _flight_mode_slots [ 5 ] ) ;
2016-01-22 11:33:40 +01:00
/* Set flag to autosave parameters if necessary */
if ( updated & & autosave_params ! = 0 & & param_changed . saved = = false ) {
/* trigger an autosave */
need_param_autosave = 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 ) ;
}
2015-02-13 23:19:43 +01:00
orb_check ( offboard_control_mode_sub , & updated ) ;
2013-01-11 07:42:09 +01:00
2013-07-31 20:58:27 +04:00
if ( updated ) {
2015-02-13 23:19:43 +01:00
orb_copy ( ORB_ID ( offboard_control_mode ) , offboard_control_mode_sub , & offboard_control_mode ) ;
2012-09-26 21:30:03 +02:00
}
2012-12-19 11:34:51 +01:00
2015-02-13 23:19:43 +01:00
if ( offboard_control_mode . timestamp ! = 0 & &
offboard_control_mode . timestamp + OFFBOARD_TIMEOUT > hrt_absolute_time ( ) ) {
2016-02-26 10:20:52 +00:00
if ( status_flags . offboard_control_signal_lost ) {
status_flags . offboard_control_signal_lost = false ;
2015-11-26 17:45:20 +01:00
status_flags . offboard_control_loss_timeout = false ;
2014-06-21 12:24:37 +02:00
status_changed = true ;
}
2014-10-23 16:17:20 +02:00
2014-06-21 12:24:37 +02:00
} else {
2016-02-26 10:20:52 +00:00
if ( ! status_flags . offboard_control_signal_lost ) {
status_flags . offboard_control_signal_lost = true ;
2016-06-02 20:43:47 +02:00
status_changed = true ;
}
2015-11-26 17:45:20 +01:00
2016-06-02 20:43:47 +02:00
/* check timer if offboard was there but now lost */
if ( ! status_flags . offboard_control_loss_timeout & & offboard_control_mode . timestamp ! = 0 ) {
2015-11-26 17:45:20 +01:00
if ( offboard_loss_timeout < FLT_EPSILON ) {
/* execute loss action immediately */
status_flags . offboard_control_loss_timeout = true ;
} else {
/* wait for timeout if set */
status_flags . offboard_control_loss_timeout = offboard_control_mode . timestamp +
2016-06-02 20:43:47 +02:00
OFFBOARD_TIMEOUT + offboard_loss_timeout * 1e6 f < hrt_absolute_time ( ) ;
}
if ( status_flags . offboard_control_loss_timeout ) {
status_changed = true ;
2015-11-26 17:45:20 +01:00
}
2014-06-21 12:24:37 +02:00
}
}
2015-07-12 12:34:48 +02:00
for ( int i = 0 ; i < ORB_MULTI_MAX_INSTANCES ; i + + ) {
2015-04-25 07:08:44 +02:00
2015-07-12 12:34:48 +02:00
if ( telemetry_subs [ i ] < 0 & & ( OK = = orb_exists ( ORB_ID ( telemetry_status ) , i ) ) ) {
telemetry_subs [ i ] = orb_subscribe_multi ( ORB_ID ( telemetry_status ) , i ) ;
2015-04-25 07:08:44 +02:00
}
2014-07-06 16:08:37 +02:00
orb_check ( telemetry_subs [ i ] , & updated ) ;
2014-06-16 17:34:21 +02:00
2014-07-06 16:08:37 +02:00
if ( updated ) {
struct telemetry_status_s telemetry ;
memset ( & telemetry , 0 , sizeof ( telemetry ) ) ;
2015-07-12 12:34:48 +02:00
orb_copy ( ORB_ID ( telemetry_status ) , telemetry_subs [ i ] , & telemetry ) ;
2014-07-06 16:08:37 +02:00
/* perform system checks when new telemetry link connected */
2016-03-15 18:25:02 +00:00
if ( /* we first connect a link or re-connect a link after loosing it */
2015-08-08 00:08:14 +02:00
( telemetry_last_heartbeat [ i ] = = 0 | | ( hrt_elapsed_time ( & telemetry_last_heartbeat [ i ] ) > 3 * 1000 * 1000 ) ) & &
/* and this link has a communication partner */
2015-08-13 23:27:16 +02:00
( telemetry . heartbeat_time > 0 ) & &
/* and it is still connected */
( hrt_elapsed_time ( & telemetry . heartbeat_time ) < 2 * 1000 * 1000 ) & &
2015-08-08 00:08:14 +02:00
/* and the system is not already armed (and potentially flying) */
! armed . armed ) {
2014-07-06 16:08:37 +02:00
2016-01-22 11:33:40 +01:00
bool chAirspeed = false ;
2016-05-04 18:34:35 -04:00
hotplug_timeout = hrt_elapsed_time ( & commander_boot_timestamp ) > HOTPLUG_SENS_TIMEOUT ;
2016-01-22 11:33:40 +01:00
2015-04-19 23:07:32 +02:00
/* Perform airspeed check only if circuit breaker is not
2016-01-22 11:33:40 +01:00
* engaged and it ' s not a rotary wing
*/
2016-02-25 17:00:39 +00:00
if ( ! status_flags . circuit_breaker_engaged_airspd_check & & ! status . is_rotary_wing ) {
2015-04-19 23:07:32 +02:00
chAirspeed = true ;
}
2015-04-19 13:57:07 +02:00
/* provide RC and sensor status feedback to the user */
2015-06-10 11:05:56 -06:00
if ( is_hil_setup ( autostart_id ) ) {
2015-06-06 07:56:48 -06:00
/* HIL configuration: check only RC input */
2016-03-15 18:25:02 +00:00
( void ) Commander : : preflightCheck ( & mavlink_log_pub , false , false , false , false , false ,
2016-07-12 12:12:59 +02:00
( status . rc_input_mode = = vehicle_status_s : : RC_IN_MODE_DEFAULT ) , /* checkGNSS */ false , /* checkDynamic */ true , /* reportFailures */ false ) ;
2015-06-06 15:03:03 -06:00
} else {
/* check sensors also */
2016-03-15 18:25:02 +00:00
( void ) Commander : : preflightCheck ( & mavlink_log_pub , true , true , true , true , chAirspeed ,
2016-07-12 12:12:59 +02:00
( status . rc_input_mode = = vehicle_status_s : : RC_IN_MODE_DEFAULT ) , ! can_arm_without_gps , /* checkDynamic */ true , hotplug_timeout ) ;
2015-06-06 07:56:48 -06:00
}
2014-07-06 16:08:37 +02:00
}
2015-11-04 18:23:19 +01:00
/* set (and don't reset) telemetry via USB as active once a MAVLink connection is up */
if ( telemetry . type = = telemetry_status_s : : TELEMETRY_STATUS_RADIO_TYPE_USB ) {
_usb_telemetry_active = true ;
}
2015-12-21 14:14:17 +01:00
if ( telemetry . heartbeat_time > 0 ) {
telemetry_last_heartbeat [ i ] = telemetry . heartbeat_time ;
}
2014-07-06 16:08:37 +02:00
}
2014-06-16 17:34:21 +02: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 ) ;
2014-10-23 16:17:20 +02:00
2014-08-24 13:44:43 +02:00
/* Check if the barometer is healthy and issue a warning in the GCS if not so.
* Because the barometer is used for calculating AMSL altitude which is used to ensure
* vertical separation from other airtraffic the operator has to know when the
* barometer is inoperational .
* */
2016-06-25 15:57:03 +02:00
hrt_abstime baro_timestamp = sensors . timestamp + sensors . baro_timestamp_relative ;
if ( hrt_elapsed_time ( & baro_timestamp ) < FAILSAFE_DEFAULT_TIMEOUT ) {
2014-08-24 13:44:43 +02:00
/* handle the case where baro was regained */
2016-02-26 11:01:12 +00:00
if ( status_flags . barometer_failure ) {
status_flags . barometer_failure = false ;
2014-08-24 13:44:43 +02:00
status_changed = true ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " baro healthy " ) ;
2014-08-24 13:44:43 +02:00
}
2014-10-23 16:17:20 +02:00
2014-08-24 13:44:43 +02:00
} else {
2016-02-26 11:01:12 +00:00
if ( ! status_flags . barometer_failure ) {
status_flags . barometer_failure = true ;
2014-08-24 13:44:43 +02:00
status_changed = true ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " baro failed " ) ;
2014-08-24 13:44:43 +02:00
}
}
2012-12-19 11:34:51 +01:00
}
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 ) ;
2013-02-25 15:48:16 +01:00
}
2014-05-25 08:22:54 +02:00
orb_check ( system_power_sub , & updated ) ;
if ( updated ) {
orb_copy ( ORB_ID ( system_power ) , system_power_sub , & system_power ) ;
if ( hrt_elapsed_time ( & system_power . timestamp ) < 200000 ) {
if ( system_power . servo_valid & &
2014-10-23 16:17:20 +02:00
! system_power . brick_valid & &
! system_power . usb_connected ) {
2014-05-25 08:22:54 +02:00
/* flying only on servo rail, this is unsafe */
2016-02-25 17:00:39 +00:00
status_flags . condition_power_input_valid = false ;
2014-10-23 16:17:20 +02:00
2014-05-25 08:22:54 +02:00
} else {
2016-02-25 17:00:39 +00:00
status_flags . condition_power_input_valid = true ;
2014-05-25 08:22:54 +02:00
}
2014-06-30 14:33:56 +02:00
/* copy avionics voltage */
2016-02-26 11:01:12 +00:00
avionics_power_rail_voltage = system_power . voltage5V_v ;
2015-10-23 17:47:22 +02:00
2015-11-04 18:23:19 +01:00
/* if the USB hardware connection went away, reboot */
2016-02-25 17:00:39 +00:00
if ( status_flags . usb_connected & & ! system_power . usb_connected ) {
2015-10-23 17:47:22 +02:00
/*
* apparently the USB cable went away but we are still powered ,
* so lets reset to a classic non - usb state .
*/
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " USB disconnected, rebooting. " )
2015-10-23 17:47:22 +02:00
usleep ( 400000 ) ;
px4_systemreset ( false ) ;
}
2015-11-04 18:23:19 +01:00
/* finally judge the USB connected state based on software detection */
2016-02-25 17:00:39 +00:00
status_flags . usb_connected = _usb_telemetry_active ;
2014-05-25 08:22:54 +02:00
}
}
2016-02-25 17:00:39 +00:00
check_valid ( diff_pres . timestamp , DIFFPRESS_TIMEOUT , true , & ( status_flags . condition_airspeed_valid ) , & status_changed ) ;
2013-08-16 23:36:49 +02: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 ) {
2015-01-15 11:09:31 +01:00
bool previous_safety_off = safety . safety_off ;
2013-07-15 22:15:15 +02:00
orb_copy ( ORB_ID ( safety ) , safety_sub , & safety ) ;
2013-11-01 09:05:28 +01:00
2014-02-17 22:45:54 +04:00
/* disarm if safety is now on and still armed */
2015-01-28 07:58:42 +01:00
if ( status . hil_state = = vehicle_status_s : : HIL_STATE_OFF & & safety . safety_switch_available & & ! safety . safety_off & & armed . armed ) {
arming_state_t new_arming_state = ( status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ? vehicle_status_s : : ARMING_STATE_STANDBY :
vehicle_status_s : : ARMING_STATE_STANDBY_ERROR ) ;
2014-05-11 13:36:51 +02:00
2016-02-24 08:00:33 +00:00
if ( TRANSITION_CHANGED = = arming_state_transition ( & status ,
2016-04-07 16:19:20 +02:00
& battery ,
2016-02-24 08:00:33 +00:00
& safety ,
new_arming_state ,
& armed ,
true /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ) {
2016-04-04 13:23:30 +02:00
mavlink_log_info ( & mavlink_log_pub , " DISARMED by safety switch " ) ;
2014-05-27 21:56:32 +02:00
arming_state_changed = true ;
2014-02-17 22:45:54 +04:00
}
}
2015-01-15 11:09:31 +01:00
//Notify the user if the status of the safety switch changes
2015-01-16 16:46:16 +01:00
if ( safety . safety_switch_available & & previous_safety_off ! = safety . safety_off ) {
2015-01-15 11:09:31 +01:00
2015-01-16 16:46:16 +01:00
if ( safety . safety_off ) {
2015-01-15 11:09:31 +01:00
set_tune ( TONE_NOTIFY_POSITIVE_TUNE ) ;
2015-01-16 16:46:16 +01:00
} else {
2015-01-15 11:09:31 +01:00
tune_neutral ( true ) ;
}
status_changed = true ;
}
2013-06-25 13:15:38 +02:00
}
2014-12-02 10:47:07 +01:00
/* update vtol vehicle status*/
orb_check ( vtol_vehicle_status_sub , & updated ) ;
if ( updated ) {
/* vtol status changed */
orb_copy ( ORB_ID ( vtol_vehicle_status ) , vtol_vehicle_status_sub , & vtol_status ) ;
2014-12-31 16:25:15 +01:00
status . vtol_fw_permanent_stab = vtol_status . fw_permanent_stab ;
2015-01-16 16:46:16 +01:00
2015-08-10 16:24:57 +02:00
/* Make sure that this is only adjusted if vehicle really is of type vtol */
2015-04-22 09:53:09 +02:00
if ( is_vtol ( & status ) ) {
2014-12-02 10:47:07 +01:00
status . is_rotary_wing = vtol_status . vtol_in_rw_mode ;
2015-08-12 15:18:43 +02:00
status . in_transition_mode = vtol_status . vtol_in_trans_mode ;
2016-02-26 11:01:12 +00:00
status_flags . vtol_transition_failure = vtol_status . vtol_transition_failsafe ;
status_flags . vtol_transition_failure_cmd = vtol_status . vtol_transition_failsafe ;
2014-12-02 10:47:07 +01:00
}
2016-01-28 10:23:23 +01:00
status_changed = true ;
2014-12-02 10:47:07 +01: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 */
2015-07-04 10:45:01 +02:00
vehicle_global_position_s gpos ;
orb_copy ( ORB_ID ( vehicle_global_position ) , global_position_sub , & gpos ) ;
/* copy to global struct if valid, with hysteresis */
// XXX consolidate this with local position handling and timeouts after release
// but we want a low-risk change now.
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_global_position_valid ) {
2015-07-04 10:45:01 +02:00
if ( gpos . eph < eph_threshold * 2.5f ) {
orb_copy ( ORB_ID ( vehicle_global_position ) , global_position_sub , & global_position ) ;
}
} else {
if ( gpos . eph < eph_threshold ) {
orb_copy ( ORB_ID ( vehicle_global_position ) , global_position_sub , & global_position ) ;
}
}
2012-12-13 10:23:02 +01:00
}
/* 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 ) ;
}
2015-10-27 09:58:54 +01:00
/* update attitude estimate */
orb_check ( attitude_sub , & updated ) ;
if ( updated ) {
/* position changed */
orb_copy ( ORB_ID ( vehicle_attitude ) , attitude_sub , & attitude ) ;
}
2015-02-11 16:42:01 +01:00
//update condition_global_position_valid
//Global positions are only published by the estimators if they are valid
2015-07-04 10:45:01 +02:00
if ( hrt_absolute_time ( ) - global_position . timestamp > POSITION_TIMEOUT ) {
2015-02-11 16:42:01 +01:00
//We have had no good fix for POSITION_TIMEOUT amount of time
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_global_position_valid ) {
2015-02-11 16:42:01 +01:00
set_tune_override ( TONE_GPS_WARNING_TUNE ) ;
status_changed = true ;
2016-02-25 17:00:39 +00:00
status_flags . condition_global_position_valid = false ;
2014-04-07 17:16:43 +04:00
}
2015-07-04 10:45:01 +02:00
} else if ( global_position . timestamp ! = 0 ) {
// Got good global position estimate
2016-02-25 17:00:39 +00:00
if ( ! status_flags . condition_global_position_valid ) {
2015-02-11 16:42:01 +01:00
status_changed = true ;
2016-02-25 17:00:39 +00:00
status_flags . condition_global_position_valid = true ;
2014-04-07 17:16:43 +04:00
}
}
2014-05-11 13:36:51 +02:00
2013-08-18 23:05:26 +02:00
/* update condition_local_position_valid and condition_local_altitude_valid */
2014-05-16 22:12:07 +02:00
/* hysteresis for EPH */
bool local_eph_good ;
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_local_position_valid ) {
2014-07-29 17:50:52 +02:00
if ( local_position . eph > eph_threshold * 2.5f ) {
2014-05-16 22:12:07 +02:00
local_eph_good = false ;
} else {
local_eph_good = true ;
}
} else {
2014-07-29 17:50:52 +02:00
if ( local_position . eph < eph_threshold ) {
2014-05-16 22:12:07 +02:00
local_eph_good = true ;
} else {
local_eph_good = false ;
}
}
2014-10-23 16:17:20 +02:00
check_valid ( local_position . timestamp , POSITION_TIMEOUT , local_position . xy_valid
2016-02-25 17:00:39 +00:00
& & local_eph_good , & ( status_flags . condition_local_position_valid ) , & status_changed ) ;
2014-10-23 16:17:20 +02:00
check_valid ( local_position . timestamp , POSITION_TIMEOUT , local_position . z_valid ,
2016-02-25 17:00:39 +00:00
& ( status_flags . condition_local_altitude_valid ) , & status_changed ) ;
2013-08-27 23:08:00 +02:00
2015-01-06 12:25:18 +01:00
/* Update land detector */
orb_check ( land_detector_sub , & updated ) ;
2015-05-24 11:43:18 +02:00
if ( updated ) {
2015-01-06 12:25:18 +01:00
orb_copy ( ORB_ID ( vehicle_land_detected ) , land_detector_sub , & land_detector ) ;
2016-04-23 15:47:59 +02:00
if ( was_landed ! = land_detector . landed ) {
2016-06-05 14:34:46 +02:00
if ( land_detector . landed ) {
2016-06-02 15:22:39 +01:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Landing detected " ) ;
2013-08-20 12:17:15 +02:00
} else {
2016-06-02 15:22:39 +01:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Takeoff detected " ) ;
2013-08-20 12:17:15 +02:00
}
}
2015-10-23 19:18:36 +02:00
2016-04-23 15:47:59 +02:00
if ( was_falling ! = land_detector . freefall ) {
if ( land_detector . freefall ) {
2016-06-02 15:22:39 +01:00
mavlink_and_console_log_info ( & mavlink_log_pub , " Freefall detected " ) ;
2016-04-23 15:47:59 +02:00
}
}
2016-06-05 14:34:46 +02:00
was_landed = land_detector . landed ;
was_falling = land_detector . freefall ;
2013-08-20 12:17:15 +02:00
}
2013-03-11 10:39:57 -07:00
2016-07-17 17:00:59 +01:00
// Check for auto-disarm
if ( armed . armed & & land_detector . landed & & disarm_when_landed > 0 ) {
auto_disarm_hysteresis . set_state_and_update ( true ) ;
} else {
auto_disarm_hysteresis . set_state_and_update ( false ) ;
}
if ( auto_disarm_hysteresis . get_state ( ) ) {
arm_disarm ( false , & mavlink_log_pub , " auto disarm on land " ) ;
}
2016-04-23 00:30:50 +02:00
if ( ! rtl_on ) {
// store the last good main_state when not in an navigation
// hold state
main_state_before_rtl = internal_state . main_state ;
}
2016-02-26 18:14:03 -08:00
orb_check ( cpuload_sub , & updated ) ;
if ( updated ) {
orb_copy ( ORB_ID ( cpuload ) , cpuload_sub , & cpuload ) ;
}
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 ) ;
2014-01-26 11:52:33 +01:00
2016-09-07 07:26:06 +02:00
/* only consider battery voltage if system has been running 6s (usb most likely detected) and battery voltage is valid */
if ( hrt_absolute_time ( ) > commander_boot_timestamp + 6000000
2016-04-23 15:12:20 +02:00
& & battery . voltage_filtered_v > 2.0f * FLT_EPSILON ) {
2016-02-24 18:08:56 +00:00
/* if battery voltage is getting lower, warn using buzzer, etc. */
if ( battery . warning = = battery_status_s : : BATTERY_WARNING_LOW & &
2016-04-27 14:37:55 +02:00
! low_battery_voltage_actions_done ) {
2016-02-24 18:08:56 +00:00
low_battery_voltage_actions_done = true ;
if ( armed . armed ) {
mavlink_log_critical ( & mavlink_log_pub , " LOW BATTERY, RETURN TO LAND ADVISED " ) ;
} else {
mavlink_log_critical ( & mavlink_log_pub , " LOW BATTERY, TAKEOFF DISCOURAGED " ) ;
}
2014-07-19 14:12:33 +02:00
2016-04-11 12:02:23 +02:00
} else if ( ! status_flags . usb_connected & &
2016-02-24 18:08:56 +00:00
battery . warning = = battery_status_s : : BATTERY_WARNING_CRITICAL & &
2016-09-07 07:26:06 +02:00
! critical_battery_voltage_actions_done ) {
2016-02-24 18:08:56 +00:00
critical_battery_voltage_actions_done = true ;
2016-04-04 13:23:30 +02:00
if ( ! armed . armed ) {
2016-02-24 18:08:56 +00:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " CRITICAL BATTERY, SHUT SYSTEM DOWN " ) ;
} else {
2016-04-23 00:30:50 +02:00
if ( low_bat_action = = 1 ) {
if ( ! rtl_on ) {
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_RTL , main_state_prev , & status_flags , & internal_state ) ) {
rtl_on = true ;
2016-04-23 15:12:20 +02:00
mavlink_and_console_log_emergency ( & mavlink_log_pub , " CRITICAL BATTERY, RETURNING TO LAND " ) ;
} else {
mavlink_and_console_log_emergency ( & mavlink_log_pub , " CRITICAL BATTERY, RTL FAILED " ) ;
2016-04-23 00:30:50 +02:00
}
}
2016-04-27 14:37:55 +02:00
} else if ( low_bat_action = = 2 ) {
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_LAND , main_state_prev , & status_flags , & internal_state ) ) {
mavlink_and_console_log_emergency ( & mavlink_log_pub , " CRITICAL BATTERY, LANDING AT CURRENT POSITION " ) ;
} else {
mavlink_and_console_log_emergency ( & mavlink_log_pub , " CRITICAL BATTERY, LANDING FAILED " ) ;
}
2016-04-23 00:30:50 +02:00
} else {
2016-04-27 14:37:55 +02:00
mavlink_and_console_log_emergency ( & mavlink_log_pub , " CRITICAL BATTERY, LANDING ADVISED! " ) ;
2016-04-23 00:30:50 +02:00
}
2016-02-24 18:08:56 +00:00
}
status_changed = true ;
}
/* End battery voltage check */
2013-08-15 17:27:29 +02:00
}
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 ) ;
2015-01-20 22:28:58 +01: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
2014-04-23 19:01:05 +02:00
/* update position setpoint triplet */
2014-04-03 20:23:34 +04:00
orb_check ( pos_sp_triplet_sub , & updated ) ;
if ( updated ) {
orb_copy ( ORB_ID ( position_setpoint_triplet ) , pos_sp_triplet_sub , & pos_sp_triplet ) ;
}
2013-02-18 16:35:34 -08:00
/* If in INIT state, try to proceed to STANDBY state */
2016-02-25 17:00:39 +00:00
if ( ! status_flags . condition_calibration_enabled & & status . arming_state = = vehicle_status_s : : ARMING_STATE_INIT ) {
2016-02-24 08:00:33 +00:00
arming_ret = arming_state_transition ( & status ,
2016-04-07 16:19:20 +02:00
& battery ,
2016-02-24 08:00:33 +00:00
& safety ,
vehicle_status_s : : ARMING_STATE_STANDBY ,
& armed ,
true /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ;
2014-05-27 21:56:32 +02:00
if ( arming_ret = = TRANSITION_CHANGED ) {
arming_state_changed = true ;
2015-10-10 01:14:42 +02:00
} else if ( arming_ret = = TRANSITION_DENIED ) {
/* do not complain if not allowed into standby */
arming_ret = TRANSITION_NOT_CHANGED ;
2014-05-27 21:56:32 +02:00
}
2013-07-28 23:12:16 +04:00
2013-02-18 16:35:34 -08:00
}
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 .
*/
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
2014-05-05 16:42:52 +02:00
/* Initialize map projection if gps is valid */
if ( ! map_projection_global_initialized ( )
2014-10-23 16:17:20 +02:00
& & ( gps_position . eph < eph_threshold )
& & ( gps_position . epv < epv_threshold )
2016-06-15 12:59:39 +02:00
& & hrt_elapsed_time ( ( hrt_abstime * ) & gps_position . timestamp ) < 1e6 ) {
2014-05-06 14:43:23 +02:00
/* set reference for global coordinates <--> local coordiantes conversion and map_projection */
2014-10-23 16:17:20 +02:00
globallocalconverter_init ( ( double ) gps_position . lat * 1.0e-7 , ( double ) gps_position . lon * 1.0e-7 ,
( float ) gps_position . alt * 1.0e-3 f , hrt_absolute_time ( ) ) ;
2014-05-05 16:42:52 +02:00
}
2015-05-14 19:29:35 +02:00
/* check if GPS is ok */
2016-02-25 17:00:39 +00:00
if ( ! status_flags . circuit_breaker_engaged_gpsfailure_check ) {
2015-05-14 19:29:35 +02:00
bool gpsIsNoisy = gps_position . noise_per_ms > 0 & & gps_position . noise_per_ms < COMMANDER_MAX_GPS_NOISE ;
//Check if GPS receiver is too noisy while we are disarmed
if ( ! armed . armed & & gpsIsNoisy ) {
2016-02-26 11:01:12 +00:00
if ( ! status_flags . gps_failure ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " GPS signal noisy " ) ;
2015-05-14 19:29:35 +02:00
set_tune_override ( TONE_GPS_WARNING_TUNE ) ;
//GPS suffers from signal jamming or excessive noise, disable GPS-aided flight
2016-02-26 11:01:12 +00:00
status_flags . gps_failure = true ;
2015-05-14 19:29:35 +02:00
status_changed = true ;
}
2014-09-21 13:32:47 +02:00
}
2014-10-23 16:17:20 +02:00
2016-06-15 12:59:39 +02:00
if ( gps_position . fix_type > = 3 & & hrt_elapsed_time ( & gps_position . timestamp ) < FAILSAFE_DEFAULT_TIMEOUT ) {
2015-05-14 19:29:35 +02:00
/* handle the case where gps was regained */
2016-02-26 11:01:12 +00:00
if ( status_flags . gps_failure & & ! gpsIsNoisy ) {
status_flags . gps_failure = false ;
2015-05-14 19:29:35 +02:00
status_changed = true ;
2016-06-30 16:59:17 +02:00
if ( status_flags . condition_home_position_valid ) {
mavlink_log_critical ( & mavlink_log_pub , " GPS fix regained " ) ;
}
2015-05-14 19:29:35 +02:00
}
2016-02-26 11:01:12 +00:00
} else if ( ! status_flags . gps_failure ) {
status_flags . gps_failure = true ;
2014-09-21 13:32:47 +02:00
status_changed = true ;
2016-04-17 19:06:00 +02:00
mavlink_log_critical ( & mavlink_log_pub , " GPS fix lost " ) ;
2014-09-21 13:32:47 +02:00
}
}
2014-07-01 09:34:26 +02:00
/* start mission result check */
2014-05-27 21:56:32 +02:00
orb_check ( mission_result_sub , & updated ) ;
if ( updated ) {
orb_copy ( ORB_ID ( mission_result ) , mission_result_sub , & mission_result ) ;
2016-02-13 01:08:07 +01:00
if ( status . mission_failure ! = mission_result . mission_failure ) {
status . mission_failure = mission_result . mission_failure ;
status_changed = true ;
if ( status . mission_failure ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " mission cannot be completed " ) ;
2016-02-13 01:08:07 +01:00
}
}
2014-12-19 22:26:31 +00:00
}
2014-08-24 17:45:15 +02:00
2014-12-19 22:26:31 +00:00
/* start geofence result check */
orb_check ( geofence_result_sub , & updated ) ;
2014-10-23 16:17:20 +02:00
2014-12-19 22:26:31 +00:00
if ( updated ) {
orb_copy ( ORB_ID ( geofence_result ) , geofence_result_sub , & geofence_result ) ;
2014-05-27 21:56:32 +02:00
}
2015-09-27 19:49:01 -04:00
// Geofence actions
if ( armed . armed & & ( geofence_result . geofence_action ! = geofence_result_s : : GF_ACTION_NONE ) ) {
static bool geofence_loiter_on = false ;
static bool geofence_rtl_on = false ;
// check for geofence violation
if ( geofence_result . geofence_violated ) {
static hrt_abstime last_geofence_violation = 0 ;
const hrt_abstime geofence_violation_action_interval = 10000000 ; // 10 seconds
if ( hrt_elapsed_time ( & last_geofence_violation ) > geofence_violation_action_interval ) {
last_geofence_violation = hrt_absolute_time ( ) ;
switch ( geofence_result . geofence_action ) {
case ( geofence_result_s : : GF_ACTION_NONE ) : {
// do nothing
break ;
}
case ( geofence_result_s : : GF_ACTION_WARN ) : {
// do nothing, mavlink critical messages are sent by navigator
break ;
}
case ( geofence_result_s : : GF_ACTION_LOITER ) : {
2016-02-26 15:41:03 +00:00
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ) {
2015-09-27 19:49:01 -04:00
geofence_loiter_on = true ;
}
break ;
}
case ( geofence_result_s : : GF_ACTION_RTL ) : {
2016-02-26 15:41:03 +00:00
if ( TRANSITION_CHANGED = = main_state_transition ( & status , commander_state_s : : MAIN_STATE_AUTO_RTL , main_state_prev , & status_flags , & internal_state ) ) {
2015-09-27 19:49:01 -04:00
geofence_rtl_on = true ;
}
break ;
}
case ( geofence_result_s : : GF_ACTION_TERMINATE ) : {
warnx ( " Flight termination because of geofence " ) ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " Geofence violation: flight termination " ) ;
2015-09-27 19:49:01 -04:00
armed . force_failsafe = true ;
status_changed = true ;
break ;
}
}
}
}
// reset if no longer in LOITER or if manually switched to LOITER
geofence_loiter_on = geofence_loiter_on
2016-02-26 15:41:03 +00:00
& & ( internal_state . main_state = = commander_state_s : : MAIN_STATE_AUTO_LOITER )
2015-09-27 19:49:01 -04:00
& & ( sp_man . loiter_switch = = manual_control_setpoint_s : : SWITCH_POS_OFF ) ;
// reset if no longer in RTL or if manually switched to RTL
geofence_rtl_on = geofence_rtl_on
2016-02-26 15:41:03 +00:00
& & ( internal_state . main_state = = commander_state_s : : MAIN_STATE_AUTO_RTL )
2015-09-27 19:49:01 -04:00
& & ( sp_man . return_switch = = manual_control_setpoint_s : : SWITCH_POS_OFF ) ;
2016-04-23 00:30:50 +02:00
rtl_on = rtl_on | | ( geofence_loiter_on | | geofence_rtl_on ) ;
}
2015-09-27 19:49:01 -04:00
2016-04-23 00:30:50 +02:00
// revert geofence failsafe transition if sticks are moved and we were previously in MANUAL or ASSIST
if ( rtl_on & &
( main_state_before_rtl = = commander_state_s : : MAIN_STATE_MANUAL | |
main_state_before_rtl = = commander_state_s : : MAIN_STATE_ALTCTL | |
main_state_before_rtl = = commander_state_s : : MAIN_STATE_POSCTL | |
main_state_before_rtl = = commander_state_s : : MAIN_STATE_ACRO | |
main_state_before_rtl = = commander_state_s : : MAIN_STATE_STAB ) ) {
// transition to previous state if sticks are increased
2016-05-05 16:55:04 +02:00
const float min_stick_change = 0.2f ;
2016-04-23 00:30:50 +02:00
if ( ( _last_sp_man . timestamp ! = sp_man . timestamp ) & &
( ( fabsf ( sp_man . x ) - fabsf ( _last_sp_man . x ) > min_stick_change ) | |
( fabsf ( sp_man . y ) - fabsf ( _last_sp_man . y ) > min_stick_change ) | |
( fabsf ( sp_man . z ) - fabsf ( _last_sp_man . z ) > min_stick_change ) | |
( fabsf ( sp_man . r ) - fabsf ( _last_sp_man . r ) > min_stick_change ) ) ) {
main_state_transition ( & status , main_state_before_rtl , main_state_prev , & status_flags , & internal_state ) ;
2015-09-27 19:49:01 -04:00
}
}
/* Check for mission flight termination */
2016-06-06 13:55:18 +02:00
if ( armed . armed & & mission_result . flight_termination & &
! status_flags . circuit_breaker_flight_termination_disabled ) {
2014-12-19 22:26:31 +00:00
armed . force_failsafe = true ;
status_changed = true ;
static bool flight_termination_printed = false ;
if ( ! flight_termination_printed ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " Geofence violation: flight termination " ) ;
2014-12-19 22:26:31 +00:00
flight_termination_printed = true ;
}
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " Flight termination active " ) ;
2014-12-19 22:26:31 +00:00
}
2015-09-27 19:49:01 -04:00
}
2014-12-19 22:26:31 +00:00
2015-06-13 18:37:19 +02:00
/* Only evaluate mission state if home is set,
* this prevents false positives for the mission
* rejection . Back off 2 seconds to not overlay
* home tune .
*/
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_home_position_valid & &
2016-05-03 16:50:12 -04:00
( hrt_elapsed_time ( & _home . timestamp ) > 2000000 ) & &
2015-06-13 18:37:19 +02:00
_last_mission_instance ! = mission_result . instance_count ) {
2015-06-15 17:03:12 +02:00
if ( ! mission_result . valid ) {
/* the mission is invalid */
tune_mission_fail ( true ) ;
warnx ( " mission fail " ) ;
} else if ( mission_result . warning ) {
/* the mission has a warning */
tune_mission_fail ( true ) ;
warnx ( " mission warning " ) ;
} else {
2015-06-13 18:37:19 +02:00
/* the mission is valid */
tune_mission_ok ( true ) ;
}
/* prevent further feedback until the mission changes */
_last_mission_instance = mission_result . instance_count ;
}
2014-06-16 17:34:21 +02:00
/* RC input check */
2016-02-26 11:01:12 +00:00
if ( ! status_flags . rc_input_blocked & & sp_man . timestamp ! = 0 & &
2015-09-04 14:57:23 +02:00
( hrt_absolute_time ( ) < sp_man . timestamp + ( uint64_t ) ( rc_loss_timeout * 1e6 f ) ) ) {
2014-01-26 14:12:27 +01:00
/* handle the case where RC signal was regained */
2016-02-26 11:01:12 +00:00
if ( ! status_flags . rc_signal_found_once ) {
status_flags . rc_signal_found_once = true ;
2014-01-26 14:12:27 +01:00
status_changed = true ;
2013-02-20 10:38:06 -08:00
2014-01-26 14:12:27 +01:00
} else {
if ( status . rc_signal_lost ) {
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " MANUAL CONTROL REGAINED after %llums " ,
2016-02-26 11:01:12 +00:00
( hrt_absolute_time ( ) - rc_signal_lost_timestamp ) / 1000 ) ;
2014-01-26 14:12:27 +01:00
status_changed = true ;
2013-02-20 10:38:06 -08:00
}
2014-01-26 14:12:27 +01:00
}
2012-12-27 18:27:08 +01:00
2014-01-26 14:12:27 +01:00
status . rc_signal_lost = false ;
2012-12-27 18:27:08 +01:00
2015-10-20 20:38:42 -04:00
/* check if left stick is in lower left position and we are in MANUAL, Rattitude, or AUTO_READY mode or (ASSIST mode and landed) -> disarm
2016-04-23 18:27:18 +02:00
* do it only for rotary wings in manual mode or fixed wing if landed */
if ( ( status . is_rotary_wing | | ( ! status . is_rotary_wing & & land_detector . landed ) ) & & status . rc_input_mode ! = vehicle_status_s : : RC_IN_MODE_OFF & &
2015-01-28 07:58:42 +01:00
( status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED | | status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED_ERROR ) & &
2016-02-26 15:41:03 +00:00
( internal_state . main_state = = commander_state_s : : MAIN_STATE_MANUAL | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_ACRO | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_STAB | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_RATTITUDE | |
2016-02-25 17:00:39 +00:00
land_detector . landed ) & &
2014-05-12 09:21:27 +02:00
sp_man . r < - STICK_ON_OFF_LIMIT & & sp_man . z < 0.1f ) {
2013-07-31 20:58:27 +04:00
2016-05-20 09:59:23 -06:00
if ( stick_off_counter > rc_arm_hyst ) {
2014-01-26 14:12:27 +01:00
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
2015-01-28 07:58:42 +01:00
arming_state_t new_arming_state = ( status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ? vehicle_status_s : : ARMING_STATE_STANDBY :
vehicle_status_s : : ARMING_STATE_STANDBY_ERROR ) ;
2016-04-07 16:19:20 +02:00
arming_ret = arming_state_transition ( & status ,
& battery ,
& safety ,
2016-02-24 08:00:33 +00:00
new_arming_state ,
& armed ,
true /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ;
2014-10-23 16:17:20 +02:00
2014-05-27 21:56:32 +02:00
if ( arming_ret = = TRANSITION_CHANGED ) {
arming_state_changed = true ;
}
2014-10-23 16:17:20 +02:00
2014-01-26 14:12:27 +01:00
stick_off_counter = 0 ;
2013-08-27 23:08:00 +02:00
2013-08-24 20:31:01 +02:00
} else {
2014-01-26 14:12:27 +01:00
stick_off_counter + + ;
2013-07-22 21:48:21 +04:00
}
2014-01-26 14:12:27 +01:00
} else {
stick_off_counter = 0 ;
}
2013-09-14 08:55:45 +02:00
2014-01-26 14:12:27 +01:00
/* check if left stick is in lower right position and we're in MANUAL mode -> arm */
2015-10-04 19:59:40 +02:00
if ( sp_man . r > STICK_ON_OFF_LIMIT & & sp_man . z < 0.1f & & status . rc_input_mode ! = vehicle_status_s : : RC_IN_MODE_OFF ) {
2016-05-20 09:59:23 -06:00
if ( stick_on_counter > rc_arm_hyst ) {
2013-09-14 08:55:45 +02:00
2014-06-26 12:14:49 +02:00
/* we check outside of the transition function here because the requirement
* for being in manual mode only applies to manual arming actions .
* the system can be armed in auto if armed via the GCS .
*/
2015-09-27 19:49:01 -04:00
2016-02-26 15:41:03 +00:00
if ( ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_MANUAL )
& & ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_ACRO )
& & ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_STAB )
2016-05-13 11:39:40 +02:00
& & ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_ALTCTL )
& & ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_POSCTL )
2016-05-21 12:08:20 +02:00
& & ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_RATTITUDE )
2016-05-13 11:39:40 +02:00
) {
2016-02-25 14:12:08 +01:00
print_reject_arm ( " NOT ARMING: Switch to a manual mode first. " ) ;
2014-10-23 16:17:20 +02:00
2016-02-25 17:00:39 +00:00
} else if ( ! status_flags . condition_home_position_valid & &
2015-09-27 19:49:01 -04:00
geofence_action = = geofence_result_s : : GF_ACTION_RTL ) {
print_reject_arm ( " NOT ARMING: Geofence RTL requires valid home " ) ;
2015-09-04 19:57:44 +02:00
} else if ( status . arming_state = = vehicle_status_s : : ARMING_STATE_STANDBY ) {
2016-02-24 08:00:33 +00:00
arming_ret = arming_state_transition ( & status ,
2016-04-07 16:19:20 +02:00
& battery ,
2016-02-24 08:00:33 +00:00
& safety ,
vehicle_status_s : : ARMING_STATE_ARMED ,
& armed ,
true /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ;
2014-10-23 16:17:20 +02:00
2014-05-27 21:56:32 +02:00
if ( arming_ret = = TRANSITION_CHANGED ) {
arming_state_changed = true ;
2015-09-23 18:36:29 +02:00
} else {
2016-03-29 22:42:57 +02:00
usleep ( 100000 ) ;
2016-05-13 11:39:40 +02:00
print_reject_arm ( " NOT ARMING: Preflight checks failed " ) ;
2014-05-27 21:56:32 +02:00
}
2013-07-28 23:12:16 +04:00
}
2013-08-24 20:31:01 +02:00
stick_on_counter = 0 ;
2014-01-26 14:12:27 +01:00
} else {
stick_on_counter + + ;
2013-07-28 23:12:16 +04:00
}
2013-02-16 13:40:09 -08:00
2014-01-26 14:12:27 +01:00
} else {
stick_on_counter = 0 ;
}
2013-02-16 13:40:09 -08:00
2014-05-27 21:56:32 +02:00
if ( arming_ret = = TRANSITION_CHANGED ) {
2015-01-28 07:58:42 +01:00
if ( status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ) {
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " ARMED by RC " ) ;
2013-08-16 23:36:49 +02:00
2014-01-26 14:12:27 +01:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " DISARMED by RC " ) ;
2013-02-20 10:38:06 -08:00
}
2014-10-23 16:17:20 +02:00
2014-05-27 21:56:32 +02:00
arming_state_changed = true ;
2013-02-20 10:38:06 -08:00
2014-05-27 21:56:32 +02:00
} else if ( arming_ret = = TRANSITION_DENIED ) {
2014-07-20 14:28:05 +02:00
/*
* the arming transition can be denied to a number of reasons :
* - pre - flight check failed ( sensors not ok or not calibrated )
* - safety not disabled
* - system not in manual mode
*/
2014-06-30 16:58:05 +02:00
tune_negative ( true ) ;
2014-01-26 14:12:27 +01:00
}
2014-01-26 11:52:33 +01:00
2014-01-26 14:12:27 +01:00
/* evaluate the main state machine according to mode switches */
2016-03-06 14:56:25 +01:00
bool first_rc_eval = ( _last_sp_man . timestamp = = 0 ) & & ( sp_man . timestamp > 0 ) ;
2016-05-09 23:01:06 +02:00
transition_result_t main_res = set_main_state_rc ( & status ) ;
2013-07-28 23:12:16 +04:00
2014-02-11 00:24:40 +01:00
/* play tune on mode change only if armed, blink LED always */
2016-03-06 14:56:25 +01:00
if ( main_res = = TRANSITION_CHANGED | | first_rc_eval ) {
2014-02-11 00:24:40 +01:00
tune_positive ( armed . armed ) ;
2014-05-27 21:56:32 +02:00
main_state_changed = true ;
2012-08-04 15:12:36 -07:00
2014-05-11 18:10:02 +02:00
} else if ( main_res = = TRANSITION_DENIED ) {
2014-01-26 14:12:27 +01:00
/* DENIED here indicates bug in the commander */
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " main state transition denied " ) ;
2014-01-26 14:12:27 +01:00
}
2012-08-08 18:47:46 +02:00
2015-12-18 21:21:51 -07:00
/* check throttle kill switch */
if ( sp_man . kill_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
/* set lockdown flag */
2016-03-06 12:48:28 +01:00
if ( ! armed . lockdown ) {
2016-03-15 18:25:02 +00:00
mavlink_log_emergency ( & mavlink_log_pub , " MANUAL KILL SWITCH ENGAGED " ) ;
2016-03-06 12:48:28 +01:00
}
2016-01-17 13:44:18 +01:00
armed . lockdown = true ;
} else if ( sp_man . kill_switch = = manual_control_setpoint_s : : SWITCH_POS_OFF ) {
2016-03-06 12:48:28 +01:00
if ( armed . lockdown ) {
2016-03-15 18:25:02 +00:00
mavlink_log_emergency ( & mavlink_log_pub , " MANUAL KILL SWITCH OFF " ) ;
2016-03-06 12:48:28 +01:00
}
2016-01-17 13:44:18 +01:00
armed . lockdown = false ;
2015-12-18 21:21:51 -07:00
}
2016-01-17 13:44:18 +01:00
/* no else case: do not change lockdown flag in unconfigured case */
2015-12-18 21:21:51 -07:00
2014-01-26 14:12:27 +01:00
} else {
2016-02-26 11:01:12 +00:00
if ( ! status_flags . rc_input_blocked & & ! status . rc_signal_lost ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " MANUAL CONTROL LOST (at t=%llums) " , hrt_absolute_time ( ) / 1000 ) ;
2014-01-26 14:12:27 +01:00
status . rc_signal_lost = true ;
2016-02-26 11:01:12 +00:00
rc_signal_lost_timestamp = sp_man . timestamp ;
2014-01-26 14:12:27 +01:00
status_changed = true ;
2012-08-08 18:47:46 +02:00
}
2013-12-14 11:03:02 +01:00
}
2014-07-06 16:08:37 +02:00
/* data links check */
bool have_link = false ;
2014-10-23 16:17:20 +02:00
2015-07-12 12:34:48 +02:00
for ( int i = 0 ; i < ORB_MULTI_MAX_INSTANCES ; i + + ) {
2014-07-24 08:57:58 +02:00
if ( telemetry_last_heartbeat [ i ] ! = 0 & &
2014-10-23 16:17:20 +02:00
hrt_elapsed_time ( & telemetry_last_heartbeat [ i ] ) < datalink_loss_timeout * 1e6 ) {
2015-04-25 10:15:15 +02:00
/* handle the case where data link was gained first time or regained,
2014-07-24 08:57:58 +02:00
* accept datalink as healthy only after datalink_regain_timeout seconds
* */
if ( telemetry_lost [ i ] & &
2014-10-23 16:17:20 +02:00
hrt_elapsed_time ( & telemetry_last_dl_loss [ i ] ) > datalink_regain_timeout * 1e6 ) {
2014-07-24 08:57:58 +02:00
2015-11-10 19:33:14 +05:30
/* report a regain */
2015-04-25 10:15:15 +02:00
if ( telemetry_last_dl_loss [ i ] > 0 ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_info ( & mavlink_log_pub , " data link #%i regained " , i ) ;
2015-11-19 17:48:39 +01:00
} else if ( telemetry_last_dl_loss [ i ] = = 0 ) {
/* new link */
2015-04-25 10:15:15 +02:00
}
2015-11-19 18:28:16 +01:00
/* got link again or new */
2016-02-25 17:00:39 +00:00
status_flags . condition_system_prearm_error_reported = false ;
2015-11-19 18:28:16 +01:00
status_changed = true ;
2014-07-06 16:08:37 +02:00
telemetry_lost [ i ] = false ;
2014-09-13 16:23:28 +02:00
have_link = true ;
2014-10-23 16:17:20 +02:00
2014-09-13 16:23:28 +02:00
} else if ( ! telemetry_lost [ i ] ) {
2014-08-16 10:52:01 +02:00
/* telemetry was healthy also in last iteration
2014-09-13 16:23:28 +02:00
* we don ' t have to check a timeout */
2014-08-16 10:52:01 +02:00
have_link = true ;
2014-07-04 21:00:05 -04:00
}
} else {
2014-10-23 16:17:20 +02:00
2014-07-06 16:08:37 +02:00
if ( ! telemetry_lost [ i ] ) {
2015-04-25 10:15:15 +02:00
/* only reset the timestamp to a different time on state change */
telemetry_last_dl_loss [ i ] = hrt_absolute_time ( ) ;
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_info ( & mavlink_log_pub , " data link #%i lost " , i ) ;
2014-07-06 16:08:37 +02:00
telemetry_lost [ i ] = true ;
2014-07-04 21:00:05 -04:00
}
2013-12-14 11:03:02 +01:00
}
}
2014-07-06 16:08:37 +02:00
if ( have_link ) {
2014-06-18 19:01:41 +02:00
/* handle the case where data link was regained */
2014-06-16 17:34:21 +02:00
if ( status . data_link_lost ) {
status . data_link_lost = false ;
status_changed = true ;
}
} else {
if ( ! status . data_link_lost ) {
2015-08-08 00:08:14 +02:00
if ( armed . armed ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " ALL DATA LINKS LOST " ) ;
2015-08-08 00:08:14 +02:00
}
2014-06-18 19:01:41 +02:00
status . data_link_lost = true ;
2014-07-20 18:23:41 +02:00
status . data_link_lost_counter + + ;
2014-06-16 17:34:21 +02:00
status_changed = true ;
2014-06-06 23:08:11 +02:00
}
}
2016-02-24 18:08:56 +00:00
/* handle commands last, as the system needs to be updated to handle them */
orb_check ( actuator_controls_sub , & updated ) ;
2014-10-23 16:17:20 +02:00
2016-02-24 18:08:56 +00:00
if ( updated ) {
/* got command */
orb_copy ( ORB_ID_VEHICLE_ATTITUDE_CONTROLS , actuator_controls_sub , & actuator_controls ) ;
2014-10-23 16:17:20 +02:00
2016-02-24 18:08:56 +00:00
/* Check engine failure
* only for fixed wing for now
*/
2016-02-25 17:00:39 +00:00
if ( ! status_flags . circuit_breaker_engaged_enginefailure_check & &
2016-02-24 18:08:56 +00:00
status . is_rotary_wing = = false & &
armed . armed & &
( ( actuator_controls . control [ 3 ] > ef_throttle_thres & &
battery . current_a / actuator_controls . control [ 3 ] <
ef_current2throttle_thres ) | |
( status . engine_failure ) ) ) {
/* potential failure, measure time */
if ( timestamp_engine_healthy > 0 & &
hrt_elapsed_time ( & timestamp_engine_healthy ) >
ef_time_thres * 1e6 & &
! status . engine_failure ) {
status . engine_failure = true ;
status_changed = true ;
2016-04-04 13:23:30 +02:00
mavlink_log_critical ( & mavlink_log_pub , " Engine Failure " ) ;
2016-02-24 18:08:56 +00:00
}
} else {
/* no failure reset flag */
timestamp_engine_healthy = hrt_absolute_time ( ) ;
if ( status . engine_failure ) {
status . engine_failure = false ;
status_changed = true ;
}
2014-09-05 08:59:00 +02:00
}
}
2016-05-10 13:57:05 +02:00
/* reset main state after takeoff has completed */
/* only switch back to posctl */
if ( main_state_prev = = commander_state_s : : MAIN_STATE_POSCTL ) {
if ( internal_state . main_state = = commander_state_s : : MAIN_STATE_AUTO_TAKEOFF
& & mission_result . finished ) {
2015-12-17 00:11:50 +01:00
2016-02-26 15:41:03 +00:00
main_state_transition ( & status , main_state_prev , main_state_prev , & status_flags , & internal_state ) ;
2015-12-17 00:11:50 +01:00
}
}
2014-09-05 08:59:00 +02:00
2013-09-22 14:58:06 +02:00
/* handle commands last, as the system needs to be updated to handle them */
orb_check ( cmd_sub , & updated ) ;
if ( updated ) {
/* got command */
orb_copy ( ORB_ID ( vehicle_command ) , cmd_sub , & cmd ) ;
/* handle it */
2015-12-12 13:01:49 +01:00
if ( handle_command ( & status , & safety , & cmd , & armed , & _home , & global_position , & local_position ,
2016-05-19 23:46:06 +02:00
& attitude , & home_pub , & command_ack_pub , & command_ack , & _roi , & roi_pub ) ) {
2013-12-29 22:38:22 +04:00
status_changed = true ;
2014-05-11 13:36:51 +02:00
}
2013-07-31 20:58:27 +04:00
}
2013-06-25 13:15:38 +02:00
2016-06-06 11:19:26 +02:00
/* Check for failure combinations which lead to flight termination */
2016-06-06 13:55:18 +02:00
if ( armed . armed & &
! status_flags . circuit_breaker_flight_termination_disabled ) {
2016-06-06 11:19:26 +02:00
/* At this point the data link and the gps system have been checked
* If we are not in a manual ( RC stick controlled mode )
* and both failed we want to terminate the flight */
if ( internal_state . main_state ! = commander_state_s : : MAIN_STATE_MANUAL & &
internal_state . main_state ! = commander_state_s : : MAIN_STATE_ACRO & &
internal_state . main_state ! = commander_state_s : : MAIN_STATE_RATTITUDE & &
internal_state . main_state ! = commander_state_s : : MAIN_STATE_STAB & &
internal_state . main_state ! = commander_state_s : : MAIN_STATE_ALTCTL & &
internal_state . main_state ! = commander_state_s : : MAIN_STATE_POSCTL & &
( ( status . data_link_lost & & status_flags . gps_failure ) | |
( status_flags . data_link_lost_cmd & & status_flags . gps_failure_cmd ) ) ) {
armed . force_failsafe = true ;
status_changed = true ;
static bool flight_termination_printed = false ;
if ( ! flight_termination_printed ) {
mavlink_and_console_log_critical ( & mavlink_log_pub , " DL and GPS lost: flight termination " ) ;
flight_termination_printed = true ;
}
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
mavlink_log_critical ( & mavlink_log_pub , " DL and GPS lost: flight termination " ) ;
}
}
/* At this point the rc signal and the gps system have been checked
* If we are in manual ( controlled with RC ) :
* if both failed we want to terminate the flight */
if ( ( internal_state . main_state = = commander_state_s : : MAIN_STATE_ACRO | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_RATTITUDE | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_MANUAL | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_STAB | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_ALTCTL | |
internal_state . main_state = = commander_state_s : : MAIN_STATE_POSCTL ) & &
( ( status . rc_signal_lost & & status_flags . gps_failure ) | |
( status_flags . rc_signal_lost_cmd & & status_flags . gps_failure_cmd ) ) ) {
armed . force_failsafe = true ;
status_changed = true ;
static bool flight_termination_printed = false ;
if ( ! flight_termination_printed ) {
warnx ( " Flight termination because of RC signal loss and GPS failure " ) ;
flight_termination_printed = true ;
}
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
mavlink_log_critical ( & mavlink_log_pub , " RC and GPS lost: flight termination " ) ;
}
}
}
2014-08-22 21:40:58 +02:00
2015-06-11 12:22:47 +02:00
/* Get current timestamp */
2015-01-16 15:51:57 +01:00
const hrt_abstime now = hrt_absolute_time ( ) ;
2013-08-17 12:37:41 +02:00
2015-06-11 12:22:47 +02:00
/* First time home position update - but only if disarmed */
2016-02-25 17:00:39 +00:00
if ( ! status_flags . condition_home_position_valid & & ! armed . armed ) {
2015-10-27 09:58:54 +01:00
commander_set_home_position ( home_pub , _home , local_position , global_position , attitude ) ;
2015-01-16 16:43:11 +01:00
}
2015-11-29 18:49:58 +01:00
/* update home position on arming if at least 500 ms from commander start spent to avoid setting home on in-air restart */
2016-02-25 17:00:39 +00:00
else if ( ( ( ! was_armed & & armed . armed ) | | ( was_landed & & ! land_detector . landed ) ) & &
2015-10-27 09:36:09 +01:00
( now > commander_boot_timestamp + INAIR_RESTART_HOLDOFF_INTERVAL ) ) {
2015-10-27 09:58:54 +01:00
commander_set_home_position ( home_pub , _home , local_position , global_position , attitude ) ;
2015-01-16 16:43:11 +01:00
}
2015-10-27 09:36:09 +01:00
was_armed = armed . armed ;
2015-01-16 16:43:11 +01:00
2014-01-25 23:37:26 +01:00
/* print new state */
if ( arming_state_changed ) {
status_changed = true ;
2014-05-27 21:56:32 +02:00
arming_state_changed = false ;
2014-01-25 23:37:26 +01:00
}
2014-05-11 13:36:51 +02:00
2014-06-16 17:34:21 +02:00
/* now set navigation state according to failsafe and main state */
2016-02-26 15:41:03 +00:00
bool nav_state_changed = set_nav_state ( & status ,
& internal_state ,
2016-04-23 16:51:10 +02:00
( datalink_loss_enabled > 0 ) ,
2014-07-23 22:58:19 +02:00
mission_result . finished ,
2016-02-25 17:00:39 +00:00
mission_result . stay_in_failsafe ,
& status_flags ,
2016-04-23 16:51:10 +02:00
land_detector . landed ,
2016-06-06 11:19:10 +02:00
( rc_loss_enabled > 0 ) ,
2015-11-26 17:45:20 +01:00
offboard_loss_act ,
offboard_loss_rc_act ) ;
2014-05-27 21:56:32 +02:00
2014-06-17 13:19:50 +02:00
if ( status . failsafe ! = failsafe_old ) {
2013-10-07 22:16:57 +02:00
status_changed = true ;
2015-01-16 16:46:16 +01:00
2014-11-10 21:38:46 +10:00
if ( status . failsafe ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " failsafe mode on " ) ;
2015-01-16 16:46:16 +01:00
2014-11-10 21:38:46 +10:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " failsafe mode off " ) ;
2014-11-10 21:38:46 +10:00
}
2015-01-16 16:46:16 +01:00
2014-06-17 13:19:50 +02:00
failsafe_old = status . failsafe ;
}
2015-06-08 15:19:41 +02:00
// TODO handle mode changes by commands
if ( main_state_changed | | nav_state_changed ) {
2014-06-17 13:19:50 +02:00
status_changed = true ;
2015-06-08 15:19:41 +02:00
main_state_changed = false ;
2013-07-31 20:58:27 +04:00
}
2013-03-26 10:44:49 -07:00
2013-08-18 12:42:24 +02:00
/* publish states (armed, control mode, vehicle status) at least with 5 Hz */
if ( counter % ( 200000 / COMMANDER_MONITORING_INTERVAL ) = = 0 | | status_changed ) {
2014-01-27 20:49:17 +01:00
set_control_mode ( ) ;
2015-01-16 15:51:57 +01:00
control_mode . timestamp = now ;
2014-01-27 20:49:17 +01:00
orb_publish ( ORB_ID ( vehicle_control_mode ) , control_mode_pub , & control_mode ) ;
2015-01-16 15:51:57 +01:00
status . timestamp = now ;
2013-07-28 23:12:16 +04:00
orb_publish ( ORB_ID ( vehicle_status ) , status_pub , & status ) ;
2014-01-27 20:49:17 +01:00
2015-01-16 15:51:57 +01:00
armed . timestamp = now ;
2015-07-22 12:42:50 +02:00
/* set prearmed state if safety is off, or safety is not present and 5 seconds passed */
if ( safety . safety_switch_available ) {
/* safety is off, go into prearmed */
armed . prearmed = safety . safety_off ;
} else {
/* safety is not present, go into prearmed
* ( all output drivers should be started / unlocked last in the boot process
* when the rest of the system is fully initialized )
*/
armed . prearmed = ( hrt_elapsed_time ( & commander_boot_timestamp ) > 5 * 1000 * 1000 ) ;
}
2013-08-18 12:42:24 +02:00
orb_publish ( ORB_ID ( actuator_armed ) , armed_pub , & armed ) ;
2012-08-16 15:49:56 +02:00
}
2013-07-31 20:58:27 +04:00
/* play arming and battery warning tunes */
2014-10-23 16:17:20 +02:00
if ( ! arm_tune_played & & armed . armed & & ( ! safety . safety_switch_available | | ( safety . safety_switch_available
& & safety . safety_off ) ) ) {
2013-07-31 20:58:27 +04:00
/* play tune when armed */
2014-02-11 00:24:40 +01:00
set_tune ( TONE_ARMING_WARNING_TUNE ) ;
2014-02-11 18:24:20 +01:00
arm_tune_played = true ;
2013-07-28 23:12:16 +04:00
2016-04-27 14:37:55 +02:00
} else if ( ! status_flags . usb_connected & &
( status . hil_state ! = vehicle_status_s : : HIL_STATE_ON ) & &
2016-02-24 18:08:56 +00:00
( battery . warning = = battery_status_s : : BATTERY_WARNING_CRITICAL ) ) {
2013-07-31 20:58:27 +04:00
/* play tune on battery critical */
2014-02-11 00:24:40 +01:00
set_tune ( TONE_BATTERY_WARNING_FAST_TUNE ) ;
2013-07-28 23:12:16 +04:00
2015-05-30 19:06:05 -07:00
} else if ( ( status . hil_state ! = vehicle_status_s : : HIL_STATE_ON ) & &
2016-02-24 18:08:56 +00:00
( battery . warning = = battery_status_s : : BATTERY_WARNING_LOW ) ) {
2014-02-11 09:13:51 +01:00
/* play tune on battery warning or failsafe */
set_tune ( TONE_BATTERY_WARNING_SLOW_TUNE ) ;
2013-07-28 23:12:16 +04:00
2014-02-11 18:24:20 +01:00
} else {
2014-02-11 00:24:40 +01:00
set_tune ( TONE_STOP_TUNE ) ;
2013-06-25 13:15:38 +02:00
}
2016-02-12 21:39:50 -08:00
2013-06-25 13:15:38 +02:00
/* reset arm_tune_played when disarmed */
2014-02-11 18:24:20 +01:00
if ( ! armed . armed | | ( safety . safety_switch_available & & ! safety . safety_off ) ) {
2015-01-15 11:09:31 +01:00
//Notify the user that it is safe to approach the vehicle
2015-01-16 16:46:16 +01:00
if ( arm_tune_played ) {
2015-01-15 11:09:31 +01:00
tune_neutral ( true ) ;
}
2013-06-25 13:15:38 +02:00
arm_tune_played = false ;
}
2016-02-12 21:39:50 -08:00
2015-11-10 19:33:14 +05:30
/* play sensor failure tunes if we already waited for hotplug sensors to come up and failed */
hotplug_timeout = hrt_elapsed_time ( & commander_boot_timestamp ) > HOTPLUG_SENS_TIMEOUT ;
2016-02-12 21:39:50 -08:00
2016-02-25 17:00:39 +00:00
if ( ! sensor_fail_tune_played & & ( ! status_flags . condition_system_sensors_initialized & & hotplug_timeout ) ) {
2015-11-10 19:33:14 +05:30
set_tune_override ( TONE_GPS_WARNING_TUNE ) ;
sensor_fail_tune_played = true ;
status_changed = true ;
}
2016-02-12 21:39:50 -08:00
2015-11-10 19:33:14 +05:30
/* update timeout flag */
2016-02-25 17:00:39 +00:00
if ( ! ( hotplug_timeout = = status_flags . condition_system_hotplug_timeout ) ) {
status_flags . condition_system_hotplug_timeout = hotplug_timeout ;
2015-11-10 19:33:14 +05:30
status_changed = true ;
}
2013-06-25 13:15:38 +02:00
2012-08-04 15:12:36 -07:00
counter + + ;
2013-08-16 18:05:59 +02:00
2013-09-19 19:58:41 +02:00
int blink_state = blink_msg_state ( ) ;
2013-10-21 20:07:47 +02:00
2013-09-19 19:58:41 +02:00
if ( blink_state > 0 ) {
/* blinking LED message, don't touch LEDs */
if ( blink_state = = 2 ) {
/* blinking LED message completed, restore normal state */
2016-02-26 18:14:03 -08:00
control_status_leds ( & status , & armed , true , & battery , & cpuload ) ;
2013-09-19 19:58:41 +02:00
}
2013-10-21 20:07:47 +02:00
2013-09-19 19:58:41 +02:00
} else {
/* normal state */
2016-02-26 18:14:03 -08:00
control_status_leds ( & status , & armed , status_changed , & battery , & cpuload ) ;
2013-09-19 19:58:41 +02:00
}
status_changed = false ;
2013-08-16 18:05:59 +02:00
2016-02-29 09:40:11 +00:00
/* publish internal state for logging purposes */
if ( commander_state_pub ! = nullptr ) {
orb_publish ( ORB_ID ( commander_state ) , commander_state_pub , & internal_state ) ;
} else {
commander_state_pub = orb_advertise ( ORB_ID ( commander_state ) , & internal_state ) ;
}
2012-08-04 15:12:36 -07:00
usleep ( COMMANDER_MONITORING_INTERVAL ) ;
}
/* wait for threads to complete */
2013-09-08 20:05:15 +02:00
ret = pthread_join ( commander_low_prio_thread , NULL ) ;
2013-09-14 08:55:45 +02:00
2013-09-08 20:05:15 +02:00
if ( ret ) {
2013-10-21 20:07:47 +02:00
warn ( " join failed: %d " , ret ) ;
2013-09-08 20:05:15 +02:00
}
rgbled_set_mode ( RGBLED_MODE_OFF ) ;
2012-08-04 15:12:36 -07:00
/* close fds */
led_deinit ( ) ;
buzzer_deinit ( ) ;
2015-07-01 11:05:45 -07:00
px4_close ( sp_man_sub ) ;
px4_close ( offboard_control_mode_sub ) ;
px4_close ( local_position_sub ) ;
px4_close ( global_position_sub ) ;
px4_close ( gps_sub ) ;
px4_close ( sensor_sub ) ;
px4_close ( safety_sub ) ;
px4_close ( cmd_sub ) ;
px4_close ( subsys_sub ) ;
px4_close ( diff_pres_sub ) ;
px4_close ( param_changed_sub ) ;
px4_close ( battery_sub ) ;
2016-02-26 10:21:33 +00:00
px4_close ( land_detector_sub ) ;
2012-08-24 00:01:23 +02: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
2015-04-27 13:29:36 +02:00
void
get_circuit_breaker_params ( )
{
2016-02-25 17:00:39 +00:00
status_flags . circuit_breaker_engaged_power_check = circuit_breaker_enabled ( " CBRK_SUPPLY_CHK " , CBRK_SUPPLY_CHK_KEY ) ;
2016-06-14 15:09:07 -04:00
status_flags . circuit_breaker_engaged_usb_check = circuit_breaker_enabled ( " CBRK_USB_CHK " , CBRK_USB_CHK_KEY ) ;
2016-02-25 17:00:39 +00:00
status_flags . circuit_breaker_engaged_airspd_check = circuit_breaker_enabled ( " CBRK_AIRSPD_CHK " , CBRK_AIRSPD_CHK_KEY ) ;
status_flags . circuit_breaker_engaged_enginefailure_check = circuit_breaker_enabled ( " CBRK_ENGINEFAIL " , CBRK_ENGINEFAIL_KEY ) ;
status_flags . circuit_breaker_engaged_gpsfailure_check = circuit_breaker_enabled ( " CBRK_GPSFAIL " , CBRK_GPSFAIL_KEY ) ;
2016-06-06 13:55:18 +02:00
status_flags . circuit_breaker_flight_termination_disabled = circuit_breaker_enabled ( " CBRK_FLIGHTTERM " , CBRK_FLIGHTTERM_KEY ) ;
2015-04-27 13:29:36 +02:00
}
2013-08-19 09:53:00 +02:00
void
check_valid ( hrt_abstime timestamp , hrt_abstime timeout , bool valid_in , bool * valid_out , bool * changed )
{
hrt_abstime t = hrt_absolute_time ( ) ;
bool valid_new = ( t < timestamp + timeout & & t > timeout & & valid_in ) ;
if ( * valid_out ! = valid_new ) {
* valid_out = valid_new ;
* changed = true ;
}
}
2016-05-06 11:10:16 +02:00
void
2016-05-06 11:11:29 +02:00
control_status_leds ( vehicle_status_s * status_local , const actuator_armed_s * actuator_armed , bool changed , battery_status_s * battery_local , const cpuload_s * cpuload_local )
2013-07-31 20:58:27 +04:00
{
2016-08-29 23:35:56 +02:00
bool overload = ( cpuload_local - > load > 0.75f ) | | ( cpuload_local - > ram_usage > 0.98f ) ;
2013-09-19 19:58:41 +02:00
/* driving rgbled */
if ( changed ) {
bool set_normal_color = false ;
2015-11-10 19:33:14 +05:30
bool hotplug_timeout = hrt_elapsed_time ( & commander_boot_timestamp ) > HOTPLUG_SENS_TIMEOUT ;
2016-02-12 21:39:50 -08:00
2013-09-19 19:58:41 +02:00
/* set mode */
2016-08-29 23:35:56 +02:00
if ( overload ) {
rgbled_set_mode ( RGBLED_MODE_BLINK_FAST ) ;
rgbled_set_color ( RGBLED_COLOR_PURPLE ) ;
set_normal_color = false ;
} else if ( status_local - > arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ) {
2013-09-19 19:58:41 +02:00
rgbled_set_mode ( RGBLED_MODE_ON ) ;
set_normal_color = true ;
2016-02-25 17:00:39 +00:00
} else if ( status_local - > arming_state = = vehicle_status_s : : ARMING_STATE_ARMED_ERROR | | ( ! status_flags . condition_system_sensors_initialized & & hotplug_timeout ) ) {
2013-09-19 19:58:41 +02:00
rgbled_set_mode ( RGBLED_MODE_BLINK_FAST ) ;
rgbled_set_color ( RGBLED_COLOR_RED ) ;
2015-01-28 07:58:42 +01:00
} else if ( status_local - > arming_state = = vehicle_status_s : : ARMING_STATE_STANDBY ) {
2013-09-19 19:58:41 +02:00
rgbled_set_mode ( RGBLED_MODE_BREATHE ) ;
set_normal_color = true ;
2016-02-12 21:39:50 -08:00
2016-02-25 17:00:39 +00:00
} else if ( ! status_flags . condition_system_sensors_initialized & & ! hotplug_timeout ) {
2015-11-10 19:33:14 +05:30
rgbled_set_mode ( RGBLED_MODE_BREATHE ) ;
set_normal_color = true ;
2013-09-19 19:58:41 +02:00
} else { // STANDBY_ERROR and other states
rgbled_set_mode ( RGBLED_MODE_BLINK_NORMAL ) ;
rgbled_set_color ( RGBLED_COLOR_RED ) ;
}
if ( set_normal_color ) {
/* set color */
2016-02-26 15:41:03 +00:00
if ( status . failsafe ) {
2015-05-13 16:23:29 +02:00
rgbled_set_color ( RGBLED_COLOR_PURPLE ) ;
2016-05-06 11:11:29 +02:00
} else if ( battery_local - > warning = = battery_status_s : : BATTERY_WARNING_LOW ) {
2014-02-11 09:13:51 +01:00
rgbled_set_color ( RGBLED_COLOR_AMBER ) ;
2016-05-06 11:11:29 +02:00
} else if ( battery_local - > warning = = battery_status_s : : BATTERY_WARNING_CRITICAL ) {
2015-05-13 16:23:29 +02:00
rgbled_set_color ( RGBLED_COLOR_RED ) ;
2013-09-19 19:58:41 +02:00
} else {
2016-02-25 17:00:39 +00:00
if ( status_flags . condition_home_position_valid & & status_flags . condition_global_position_valid ) {
2013-09-19 19:58:41 +02:00
rgbled_set_color ( RGBLED_COLOR_GREEN ) ;
} else {
rgbled_set_color ( RGBLED_COLOR_BLUE ) ;
}
}
}
}
2016-08-27 08:07:48 -04:00
# if defined (CONFIG_ARCH_BOARD_PX4FMU_V1) || defined (CONFIG_ARCH_BOARD_PX4FMU_V4) || defined (CONFIG_ARCH_BOARD_CRAZYFLIE)
2013-08-27 23:08:00 +02:00
2013-08-16 18:05:59 +02:00
/* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
2013-11-01 09:05:28 +01:00
if ( actuator_armed - > armed ) {
2013-08-16 18:05:59 +02:00
/* armed, solid */
led_on ( LED_BLUE ) ;
2013-11-01 09:05:28 +01:00
} else if ( actuator_armed - > ready_to_arm ) {
2013-08-16 18:05:59 +02:00
/* ready to arm, blink at 1Hz */
2014-05-11 13:36:51 +02:00
if ( leds_counter % 20 = = 0 ) {
2013-08-16 18:05:59 +02:00
led_toggle ( LED_BLUE ) ;
2014-05-11 13:36:51 +02:00
}
2013-08-27 23:08:00 +02:00
2013-08-16 18:05:59 +02:00
} else {
/* not ready to arm, blink at 10Hz */
2014-05-11 13:36:51 +02:00
if ( leds_counter % 2 = = 0 ) {
2013-08-16 18:05:59 +02:00
led_toggle ( LED_BLUE ) ;
2014-05-11 13:36:51 +02:00
}
2013-08-16 18:05:59 +02:00
}
2013-08-27 23:08:00 +02:00
2013-08-16 18:05:59 +02:00
# endif
2016-08-29 23:35:56 +02:00
/* give system warnings on error LED */
if ( overload ) {
2014-05-11 13:36:51 +02:00
if ( leds_counter % 2 = = 0 ) {
2013-08-16 18:05:59 +02:00
led_toggle ( LED_AMBER ) ;
2014-05-11 13:36:51 +02:00
}
2013-08-27 23:08:00 +02:00
2013-08-16 18:05:59 +02:00
} else {
led_off ( LED_AMBER ) ;
2013-07-31 20:58:27 +04:00
}
leds_counter + + ;
}
2013-07-28 23:12:16 +04:00
transition_result_t
2016-05-09 23:01:06 +02:00
set_main_state_rc ( struct vehicle_status_s * status_local )
2013-07-28 23:12:16 +04:00
{
2014-01-27 20:49:17 +01:00
/* set main state according to RC switches */
2013-07-28 23:12:16 +04:00
transition_result_t res = TRANSITION_DENIED ;
2016-03-06 14:56:25 +01:00
// XXX this should not be necessary any more, we should be able to
// just delete this and respond to mode switches
2015-09-27 19:49:01 -04:00
/* if offboard is set already by a mavlink command, abort */
2016-02-26 10:20:52 +00:00
if ( status_flags . offboard_control_set_by_command ) {
2016-04-04 13:23:30 +02:00
return main_state_transition ( status_local , commander_state_s : : MAIN_STATE_OFFBOARD , main_state_prev , & status_flags , & internal_state ) ;
2014-07-16 09:38:57 +02:00
}
2015-10-07 16:35:51 +02:00
/* manual setpoint has not updated, do not re-evaluate it */
2016-05-09 23:01:06 +02:00
if ( ( ( _last_sp_man . timestamp ! = 0 ) & & ( _last_sp_man . timestamp = = sp_man . timestamp ) ) | |
( ( _last_sp_man . offboard_switch = = sp_man . offboard_switch ) & &
( _last_sp_man . return_switch = = sp_man . return_switch ) & &
( _last_sp_man . mode_switch = = sp_man . mode_switch ) & &
( _last_sp_man . acro_switch = = sp_man . acro_switch ) & &
( _last_sp_man . rattitude_switch = = sp_man . rattitude_switch ) & &
( _last_sp_man . posctl_switch = = sp_man . posctl_switch ) & &
( _last_sp_man . loiter_switch = = sp_man . loiter_switch ) & &
( _last_sp_man . mode_slot = = sp_man . mode_slot ) ) ) {
2015-09-27 19:49:01 -04:00
// update these fields for the geofence system
2016-05-05 16:55:04 +02:00
if ( ! rtl_on ) {
2016-05-09 23:01:06 +02:00
_last_sp_man . timestamp = sp_man . timestamp ;
_last_sp_man . x = sp_man . x ;
_last_sp_man . y = sp_man . y ;
_last_sp_man . z = sp_man . z ;
_last_sp_man . r = sp_man . r ;
2016-05-05 16:55:04 +02:00
}
2015-10-07 16:35:51 +02:00
/* no timestamp change or no switch change -> nothing changed */
return TRANSITION_NOT_CHANGED ;
}
2016-05-09 23:01:06 +02:00
_last_sp_man = sp_man ;
2015-10-07 16:35:51 +02:00
2014-01-29 21:21:16 +01:00
/* offboard switch overrides main switch */
2016-05-09 23:01:06 +02:00
if ( sp_man . offboard_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_OFFBOARD , main_state_prev , & status_flags , & internal_state ) ;
2014-10-23 16:17:20 +02:00
2014-01-29 21:21:16 +01:00
if ( res = = TRANSITION_DENIED ) {
2014-07-13 11:45:02 +02:00
print_reject_mode ( status_local , " OFFBOARD " ) ;
2015-04-19 16:20:07 +02:00
/* mode rejected, continue to evaluate the main system mode */
2013-07-28 23:12:16 +04:00
2014-01-29 21:21:16 +01:00
} else {
2015-04-19 16:20:07 +02:00
/* changed successfully or already in this state */
2014-01-29 21:21:16 +01:00
return res ;
}
}
2013-07-28 23:12:16 +04:00
2015-04-19 16:20:07 +02:00
/* RTL switch overrides main switch */
2016-05-09 23:01:06 +02:00
if ( sp_man . return_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-03-06 12:48:28 +01:00
warnx ( " RTL switch changed and ON! " ) ;
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_RTL , main_state_prev , & status_flags , & internal_state ) ;
2015-04-19 16:20:07 +02:00
if ( res = = TRANSITION_DENIED ) {
2016-03-06 12:34:31 +01:00
print_reject_mode ( status_local , " AUTO RTL " ) ;
2015-04-19 16:20:07 +02:00
/* fallback to LOITER if home position not set */
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ;
2015-04-20 22:00:36 +02:00
}
2015-04-19 16:20:07 +02:00
2015-04-20 22:00:36 +02:00
if ( res ! = TRANSITION_DENIED ) {
/* changed successfully or already in this state */
2014-01-29 21:21:16 +01:00
return res ;
}
2015-04-20 22:00:36 +02:00
/* if we get here mode was rejected, continue to evaluate the main system mode */
2014-01-29 21:21:16 +01:00
}
2013-07-28 23:12:16 +04:00
2016-03-04 11:47:33 +01:00
/* we know something has changed - check if we are in mode slot operation */
2016-05-09 23:01:06 +02:00
if ( sp_man . mode_slot ! = manual_control_setpoint_s : : MODE_SLOT_NONE ) {
2016-03-04 11:47:33 +01:00
2016-05-09 23:01:06 +02:00
if ( sp_man . mode_slot > = sizeof ( _flight_mode_slots ) / sizeof ( _flight_mode_slots [ 0 ] ) ) {
warnx ( " m slot overflow " ) ;
2016-03-04 11:47:33 +01:00
return TRANSITION_DENIED ;
}
2016-05-09 23:01:06 +02:00
int new_mode = _flight_mode_slots [ sp_man . mode_slot ] ;
2016-03-04 11:47:33 +01:00
if ( new_mode < 0 ) {
/* slot is unused */
res = TRANSITION_NOT_CHANGED ;
2016-03-06 12:34:31 +01:00
2016-03-04 11:47:33 +01:00
} else {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
2016-03-06 12:34:31 +01:00
2016-04-26 09:11:35 +02:00
/* ensure that the mode selection does not get stuck here */
int maxcount = 5 ;
2016-03-06 12:34:31 +01:00
/* enable the use of break */
2016-04-18 18:29:07 +02:00
/* fallback strategies, give the user the closest mode to what he wanted */
2016-04-26 09:11:35 +02:00
while ( res = = TRANSITION_DENIED & & maxcount > 0 ) {
maxcount - - ;
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_MISSION ) {
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
/* fall back to loiter */
new_mode = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
print_reject_mode ( status_local , " AUTO MISSION " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
2016-03-06 12:34:31 +01:00
}
2016-04-18 18:29:07 +02:00
}
2016-03-06 12:34:31 +01:00
2016-04-26 09:11:35 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_RTL ) {
/* fall back to position control */
new_mode = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
print_reject_mode ( status_local , " AUTO RTL " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
}
}
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_LAND ) {
/* fall back to position control */
new_mode = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
print_reject_mode ( status_local , " AUTO LAND " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
}
}
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_TAKEOFF ) {
/* fall back to position control */
new_mode = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
print_reject_mode ( status_local , " AUTO TAKEOFF " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
}
}
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_FOLLOW_TARGET ) {
/* fall back to position control */
new_mode = commander_state_s : : MAIN_STATE_AUTO_LOITER ;
print_reject_mode ( status_local , " AUTO FOLLOW " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
}
}
2016-04-18 18:29:07 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_AUTO_LOITER ) {
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
/* fall back to position control */
new_mode = commander_state_s : : MAIN_STATE_POSCTL ;
2016-04-26 09:11:35 +02:00
print_reject_mode ( status_local , " AUTO HOLD " ) ;
2016-04-18 18:29:07 +02:00
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
2016-03-06 12:34:31 +01:00
}
2016-04-18 18:29:07 +02:00
}
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_POSCTL ) {
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
/* fall back to altitude control */
new_mode = commander_state_s : : MAIN_STATE_ALTCTL ;
print_reject_mode ( status_local , " POSITION CONTROL " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
2016-03-06 12:34:31 +01:00
}
2016-04-18 18:29:07 +02:00
}
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_ALTCTL ) {
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
/* fall back to stabilized */
new_mode = commander_state_s : : MAIN_STATE_STAB ;
print_reject_mode ( status_local , " ALTITUDE CONTROL " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
2016-03-06 12:34:31 +01:00
}
2016-04-18 18:29:07 +02:00
}
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
if ( new_mode = = commander_state_s : : MAIN_STATE_STAB ) {
2016-03-06 12:34:31 +01:00
2016-04-18 18:29:07 +02:00
/* fall back to manual */
new_mode = commander_state_s : : MAIN_STATE_MANUAL ;
print_reject_mode ( status_local , " STABILIZED " ) ;
res = main_state_transition ( status_local , new_mode , main_state_prev , & status_flags , & internal_state ) ;
if ( res ! = TRANSITION_DENIED ) {
break ;
2016-03-06 12:34:31 +01:00
}
}
2016-04-18 18:29:07 +02:00
}
2016-03-04 11:47:33 +01:00
}
2016-03-15 18:25:02 +00:00
2016-03-04 11:47:33 +01:00
return res ;
}
2015-04-19 16:20:07 +02:00
/* offboard and RTL switches off or denied, check main mode switch */
2016-05-09 23:01:06 +02:00
switch ( sp_man . mode_switch ) {
2015-01-28 07:58:42 +01:00
case manual_control_setpoint_s : : SWITCH_POS_NONE :
2014-04-06 20:04:18 +04:00
res = TRANSITION_NOT_CHANGED ;
break ;
2015-01-28 07:58:42 +01:00
case manual_control_setpoint_s : : SWITCH_POS_OFF : // MANUAL
2016-05-09 23:01:06 +02:00
if ( sp_man . acro_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2015-05-17 12:58:44 +02:00
/* manual mode is stabilized already for multirotors, so switch to acro
* for any non - manual mode
*/
2016-03-10 15:48:35 +01:00
// XXX: put ACRO and STAB on separate switches
if ( status . is_rotary_wing & & ! status . is_vtol ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_ACRO , main_state_prev , & status_flags , & internal_state ) ;
2016-03-10 15:48:35 +01:00
} else if ( ! status . is_rotary_wing ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_STAB , main_state_prev , & status_flags , & internal_state ) ;
2016-03-10 15:48:35 +01:00
} else {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2015-05-17 12:58:44 +02:00
}
2014-05-20 00:03:00 +02:00
2016-02-12 21:39:50 -08:00
}
2016-05-09 23:01:06 +02:00
else if ( sp_man . rattitude_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-02-12 21:39:50 -08:00
/* Similar to acro transitions for multirotors. FW aircraft don't need a
2015-10-20 20:38:42 -04:00
* rattitude mode . */
if ( status . is_rotary_wing ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_RATTITUDE , main_state_prev , & status_flags , & internal_state ) ;
2015-10-20 20:38:42 -04:00
} else {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_STAB , main_state_prev , & status_flags , & internal_state ) ;
2015-10-20 20:38:42 -04:00
}
} else {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2014-01-31 22:44:05 +01:00
}
2014-10-23 16:17:20 +02:00
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
2015-01-28 07:58:42 +01:00
case manual_control_setpoint_s : : SWITCH_POS_MIDDLE : // ASSIST
2016-05-09 23:01:06 +02:00
if ( sp_man . posctl_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_POSCTL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-28 23:12:16 +04:00
2014-04-03 20:23:34 +04:00
if ( res ! = TRANSITION_DENIED ) {
2013-07-28 23:12:16 +04:00
break ; // changed successfully or already in this state
2014-04-03 20:23:34 +04:00
}
2013-07-28 23:12:16 +04:00
2016-03-06 12:34:31 +01:00
print_reject_mode ( status_local , " POSITION CONTROL " ) ;
2013-07-28 23:12:16 +04:00
}
2014-10-23 16:17:20 +02:00
// fallback to ALTCTL
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_ALTCTL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-28 23:12:16 +04:00
2014-04-03 20:23:34 +04:00
if ( res ! = TRANSITION_DENIED ) {
2013-07-28 23:12:16 +04:00
break ; // changed successfully or already in this mode
2014-04-03 20:23:34 +04:00
}
2013-07-28 23:12:16 +04:00
2016-05-09 23:01:06 +02:00
if ( sp_man . posctl_switch ! = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-03-06 12:34:31 +01:00
print_reject_mode ( status_local , " ALTITUDE CONTROL " ) ;
2014-04-03 20:23:34 +04:00
}
2013-07-31 20:58:27 +04:00
2014-06-25 17:56:11 +02:00
// fallback to MANUAL
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
2015-01-28 07:58:42 +01:00
case manual_control_setpoint_s : : SWITCH_POS_ON : // AUTO
2016-05-09 23:01:06 +02:00
if ( sp_man . loiter_switch = = manual_control_setpoint_s : : SWITCH_POS_ON ) {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ;
2014-05-27 23:24:01 +02:00
if ( res ! = TRANSITION_DENIED ) {
break ; // changed successfully or already in this state
}
2014-06-25 17:56:11 +02:00
2016-03-06 12:34:31 +01:00
print_reject_mode ( status_local , " AUTO PAUSE " ) ;
2014-06-25 17:56:11 +02:00
2014-05-27 23:24:01 +02:00
} else {
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_MISSION , main_state_prev , & status_flags , & internal_state ) ;
2014-05-27 23:24:01 +02:00
if ( res ! = TRANSITION_DENIED ) {
break ; // changed successfully or already in this state
}
2014-06-25 17:56:11 +02:00
2016-03-06 12:34:31 +01:00
print_reject_mode ( status_local , " AUTO MISSION " ) ;
2014-07-06 21:37:26 +02:00
2014-10-23 16:17:20 +02:00
// fallback to LOITER if home position not set
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_AUTO_LOITER , main_state_prev , & status_flags , & internal_state ) ;
2014-07-06 21:37:26 +02:00
2014-10-23 16:17:20 +02:00
if ( res ! = TRANSITION_DENIED ) {
break ; // changed successfully or already in this state
}
2014-04-03 20:23:34 +04:00
}
2013-07-28 23:12:16 +04:00
2014-10-23 16:17:20 +02:00
// fallback to POSCTL
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_POSCTL , main_state_prev , & status_flags , & internal_state ) ;
2014-06-25 17:56:11 +02:00
2014-10-23 16:17:20 +02:00
if ( res ! = TRANSITION_DENIED ) {
break ; // changed successfully or already in this state
}
2014-06-25 17:56:11 +02:00
// fallback to ALTCTL
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_ALTCTL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-28 23:12:16 +04:00
2014-04-03 20:23:34 +04:00
if ( res ! = TRANSITION_DENIED ) {
2013-07-28 23:12:16 +04:00
break ; // changed successfully or already in this state
2014-04-03 20:23:34 +04:00
}
2013-07-28 23:12:16 +04:00
2014-06-25 17:56:11 +02:00
// fallback to MANUAL
2016-04-04 13:23:30 +02:00
res = main_state_transition ( status_local , commander_state_s : : MAIN_STATE_MANUAL , main_state_prev , & status_flags , & internal_state ) ;
2013-07-28 23:12:16 +04:00
// TRANSITION_DENIED is not possible here
break ;
default :
break ;
}
return res ;
}
2014-01-27 20:49:17 +01:00
void
set_control_mode ( )
{
2014-05-27 21:56:32 +02:00
/* set vehicle_control_mode according to set_navigation_state */
2014-01-27 20:49:17 +01:00
control_mode . flag_armed = armed . armed ;
2014-12-23 21:50:16 +01:00
control_mode . flag_external_manual_override_ok = ( ! status . is_rotary_wing & & ! status . is_vtol ) ;
2016-01-20 22:04:31 -08:00
control_mode . flag_system_hil_enabled = status . hil_state = = vehicle_status_s : : HIL_STATE_ON ;
2014-02-17 16:50:00 +04:00
control_mode . flag_control_offboard_enabled = false ;
2014-01-27 20:49:17 +01:00
2014-06-16 17:34:21 +02:00
switch ( status . nav_state ) {
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_MANUAL :
2014-05-27 21:56:32 +02:00
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
2015-08-19 17:54:57 +02:00
control_mode . flag_control_rates_enabled = stabilization_required ( ) ;
control_mode . flag_control_attitude_enabled = stabilization_required ( ) ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = false ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_termination_enabled = false ;
break ;
2014-12-04 14:23:19 +01:00
2015-05-17 12:58:44 +02:00
case vehicle_status_s : : NAVIGATION_STATE_STAB :
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = true ;
2015-05-17 12:58:44 +02:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = false ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2015-05-17 12:58:44 +02:00
control_mode . flag_control_termination_enabled = false ;
2015-05-28 23:01:19 -07:00
/* override is not ok in stabilized mode */
control_mode . flag_external_manual_override_ok = false ;
2015-05-17 12:58:44 +02:00
break ;
2015-10-20 20:38:42 -04:00
case vehicle_status_s : : NAVIGATION_STATE_RATTITUDE :
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-04-21 21:25:59 -06:00
control_mode . flag_control_rattitude_enabled = true ;
2015-10-20 20:38:42 -04:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = false ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2015-10-20 20:38:42 -04:00
control_mode . flag_control_termination_enabled = false ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_ALTCTL :
2014-05-27 21:56:32 +02:00
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_altitude_enabled = true ;
control_mode . flag_control_climb_rate_enabled = true ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_termination_enabled = false ;
break ;
2014-01-27 20:49:17 +01:00
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_POSCTL :
2014-05-27 21:56:32 +02:00
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_altitude_enabled = true ;
control_mode . flag_control_climb_rate_enabled = true ;
2015-08-13 09:00:15 +02:00
control_mode . flag_control_position_enabled = ! status . in_transition_mode ;
control_mode . flag_control_velocity_enabled = ! status . in_transition_mode ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_termination_enabled = false ;
2014-01-27 20:49:17 +01:00
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_RTL :
case vehicle_status_s : : NAVIGATION_STATE_AUTO_RCRECOVER :
2015-06-13 00:16:25 +02:00
/* override is not ok for the RTL and recovery mode */
control_mode . flag_external_manual_override_ok = false ;
/* fallthrough */
2016-02-18 06:57:01 -08:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_FOLLOW_TARGET :
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_RTGS :
2016-03-13 15:39:35 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_LAND :
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_LANDENGFAIL :
2015-06-13 00:16:25 +02:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_MISSION :
case vehicle_status_s : : NAVIGATION_STATE_AUTO_LOITER :
2015-11-22 16:03:58 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_TAKEOFF :
2014-05-27 21:56:32 +02:00
control_mode . flag_control_manual_enabled = false ;
control_mode . flag_control_auto_enabled = true ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_altitude_enabled = true ;
control_mode . flag_control_climb_rate_enabled = true ;
2016-01-14 14:25:22 +01:00
control_mode . flag_control_position_enabled = ! status . in_transition_mode ;
control_mode . flag_control_velocity_enabled = ! status . in_transition_mode ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-05-27 21:56:32 +02:00
control_mode . flag_control_termination_enabled = false ;
2014-01-27 20:49:17 +01:00
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_AUTO_LANDGPSFAIL :
2014-08-22 00:40:45 +02:00
control_mode . flag_control_manual_enabled = false ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-08-22 00:40:45 +02:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = true ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-08-22 00:40:45 +02:00
control_mode . flag_control_termination_enabled = false ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_ACRO :
2014-11-13 09:43:51 +10:00
control_mode . flag_control_manual_enabled = true ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = false ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-11-13 09:43:51 +10:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = false ;
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-11-13 09:43:51 +10:00
control_mode . flag_control_termination_enabled = false ;
2016-02-25 17:00:39 +00:00
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_DESCEND :
2014-11-13 09:43:51 +10:00
/* TODO: check if this makes sense */
control_mode . flag_control_manual_enabled = false ;
control_mode . flag_control_auto_enabled = true ;
control_mode . flag_control_rates_enabled = true ;
control_mode . flag_control_attitude_enabled = true ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-11-13 09:43:51 +10:00
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-11-13 09:43:51 +10:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = true ;
control_mode . flag_control_termination_enabled = false ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_TERMINATION :
2014-01-27 20:49:17 +01:00
/* disable all controllers on termination */
control_mode . flag_control_manual_enabled = false ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_rates_enabled = false ;
control_mode . flag_control_attitude_enabled = false ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2014-01-27 20:49:17 +01:00
control_mode . flag_control_position_enabled = false ;
control_mode . flag_control_velocity_enabled = false ;
2016-03-09 12:47:08 -08:00
control_mode . flag_control_acceleration_enabled = false ;
2014-01-27 20:49:17 +01:00
control_mode . flag_control_altitude_enabled = false ;
control_mode . flag_control_climb_rate_enabled = false ;
control_mode . flag_control_termination_enabled = true ;
break ;
2015-01-28 07:58:42 +01:00
case vehicle_status_s : : NAVIGATION_STATE_OFFBOARD :
2014-11-13 09:43:51 +10:00
control_mode . flag_control_manual_enabled = false ;
control_mode . flag_control_auto_enabled = false ;
control_mode . flag_control_offboard_enabled = true ;
2015-02-13 23:19:43 +01:00
/*
* The control flags depend on what is ignored according to the offboard control mode topic
* Inner loop flags ( e . g . attitude ) also depend on outer loop ignore flags ( e . g . position )
*/
control_mode . flag_control_rates_enabled = ! offboard_control_mode . ignore_bodyrate | |
! offboard_control_mode . ignore_attitude | |
! offboard_control_mode . ignore_position | |
! offboard_control_mode . ignore_velocity | |
! offboard_control_mode . ignore_acceleration_force ;
control_mode . flag_control_attitude_enabled = ! offboard_control_mode . ignore_attitude | |
! offboard_control_mode . ignore_position | |
! offboard_control_mode . ignore_velocity | |
! offboard_control_mode . ignore_acceleration_force ;
2016-02-26 13:40:42 +00:00
control_mode . flag_control_rattitude_enabled = false ;
2016-02-26 18:14:03 -08:00
control_mode . flag_control_acceleration_enabled = ! offboard_control_mode . ignore_acceleration_force & &
! status . in_transition_mode ;
2016-04-20 12:13:20 -07:00
2015-08-07 16:43:16 +02:00
control_mode . flag_control_velocity_enabled = ( ! offboard_control_mode . ignore_velocity | |
2016-02-26 18:14:03 -08:00
! offboard_control_mode . ignore_position ) & & ! status . in_transition_mode & &
2016-04-07 15:09:21 -07:00
! control_mode . flag_control_acceleration_enabled ;
2015-02-13 23:19:43 +01:00
2016-04-07 15:09:21 -07:00
control_mode . flag_control_climb_rate_enabled = ( ! offboard_control_mode . ignore_velocity | |
! offboard_control_mode . ignore_position ) & & ! control_mode . flag_control_acceleration_enabled ;
2015-02-13 23:19:43 +01:00
2016-02-26 18:14:03 -08:00
control_mode . flag_control_position_enabled = ! offboard_control_mode . ignore_position & & ! status . in_transition_mode & &
2016-04-07 15:09:21 -07:00
! control_mode . flag_control_acceleration_enabled ;
2015-02-13 23:19:43 +01:00
2016-04-07 15:09:21 -07:00
control_mode . flag_control_altitude_enabled = ( ! offboard_control_mode . ignore_velocity | |
! offboard_control_mode . ignore_position ) & & ! control_mode . flag_control_acceleration_enabled ;
2015-01-16 16:46:16 +01:00
2014-11-13 09:43:51 +10:00
break ;
2014-01-27 20:49:17 +01:00
default :
break ;
}
}
2015-08-19 17:54:57 +02:00
bool
stabilization_required ( )
{
return ( status . is_rotary_wing | | // is a rotary wing, or
status . vtol_fw_permanent_stab | | // is a VTOL in fixed wing mode and stabilisation is on, or
( vtol_status . vtol_in_trans_mode & & // is currently a VTOL transitioning AND
! status . is_rotary_wing ) ) ; // is a fixed wing, ie: transitioning back to rotary wing mode
}
2013-07-31 20:58:27 +04:00
void
2014-07-13 11:43:56 +02:00
print_reject_mode ( struct vehicle_status_s * status_local , const char * msg )
2013-07-31 20:58:27 +04:00
{
hrt_abstime t = hrt_absolute_time ( ) ;
if ( t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL ) {
last_print_mode_reject_time = t ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " REJECT %s " , msg ) ;
2014-02-01 13:21:51 +01:00
2014-02-11 00:24:40 +01:00
/* only buzz if armed, because else we're driving people nuts indoors
they really need to look at the leds as well . */
tune_negative ( armed . armed ) ;
2013-07-31 20:58:27 +04:00
}
}
2013-08-16 09:23:39 +02:00
void
print_reject_arm ( 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 ;
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , msg ) ;
2014-02-11 00:24:40 +01:00
tune_negative ( true ) ;
2013-08-16 09:23:39 +02:00
}
}
2015-12-12 13:01:49 +01:00
void answer_command ( struct vehicle_command_s & cmd , unsigned result ,
orb_advert_t & command_ack_pub , vehicle_command_ack_s & command_ack )
2013-08-22 15:57:17 +02:00
{
switch ( result ) {
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED :
2015-01-16 16:46:16 +01:00
tune_positive ( true ) ;
2013-08-27 23:08:00 +02:00
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED :
2014-02-11 00:24:40 +01:00
tune_negative ( true ) ;
2013-08-27 23:08:00 +02:00
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_RESULT_FAILED :
2014-02-11 00:24:40 +01:00
tune_negative ( true ) ;
2013-08-27 23:08:00 +02:00
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED :
2014-02-11 00:24:40 +01:00
tune_negative ( true ) ;
2013-08-27 23:08:00 +02:00
break ;
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_RESULT_UNSUPPORTED :
2014-02-11 00:24:40 +01:00
tune_negative ( true ) ;
2013-08-27 23:08:00 +02:00
break ;
default :
break ;
2013-08-22 15:57:17 +02:00
}
2015-12-12 13:01:49 +01:00
/* publish ACK */
command_ack . command = cmd . command ;
command_ack . result = result ;
if ( command_ack_pub ! = nullptr ) {
orb_publish ( ORB_ID ( vehicle_command_ack ) , command_ack_pub , & command_ack ) ;
} else {
command_ack_pub = orb_advertise ( ORB_ID ( vehicle_command_ack ) , & command_ack ) ;
}
2013-08-22 15:57:17 +02: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 */
2016-01-07 15:09:38 -08:00
px4_prctl ( PR_SET_NAME , " commander_low_prio " , px4_getpid ( ) ) ;
2013-03-25 14:53:54 -07:00
2013-08-17 18:39:46 +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 ) ) ;
2015-12-12 13:01:49 +01:00
/* command ack */
orb_advert_t command_ack_pub = nullptr ;
struct vehicle_command_ack_s command_ack ;
memset ( & command_ack , 0 , sizeof ( command_ack ) ) ;
2015-03-23 10:52:32 -07:00
/* timeout for param autosave */
2015-04-03 16:14:04 +02:00
hrt_abstime need_param_autosave_timeout = 0 ;
2015-03-23 10:52:32 -07:00
2013-08-17 18:39:46 +02:00
/* wakeup source(s) */
2015-04-24 01:24:31 -07:00
px4_pollfd_struct_t fds [ 1 ] ;
2013-08-17 18:39:46 +02:00
/* use the gyro to pace output - XXX BROKEN if we are using the L3GD20 */
fds [ 0 ] . fd = cmd_sub ;
fds [ 0 ] . events = POLLIN ;
2013-08-15 09:52:22 +02:00
2013-03-25 14:53:54 -07:00
while ( ! thread_should_exit ) {
2015-03-28 13:06:05 -07:00
/* wait for up to 1000ms for data */
2015-04-24 01:24:31 -07:00
int pret = px4_poll ( & fds [ 0 ] , ( sizeof ( fds ) / sizeof ( fds [ 0 ] ) ) , 1000 ) ;
2013-03-25 14:53:54 -07:00
2013-10-21 20:07:47 +02:00
/* timed out - periodic check for thread_should_exit, etc. */
2014-05-11 13:36:51 +02:00
if ( pret = = 0 ) {
2015-03-28 13:06:05 -07:00
/* trigger a param autosave if required */
2015-04-03 16:14:04 +02:00
if ( need_param_autosave ) {
if ( need_param_autosave_timeout > 0 & & hrt_elapsed_time ( & need_param_autosave_timeout ) > 200000ULL ) {
2015-03-28 13:06:05 -07:00
int ret = param_save_default ( ) ;
2015-11-02 18:48:53 +01:00
if ( ret ! = OK ) {
2016-03-15 18:25:02 +00:00
mavlink_and_console_log_critical ( & mavlink_log_pub , " settings auto save error " ) ;
2015-11-03 08:57:30 +01:00
} else {
2016-06-01 15:39:23 +01:00
PX4_DEBUG ( " commander: settings saved. " ) ;
2015-03-28 13:06:05 -07:00
}
2015-04-03 16:14:04 +02:00
need_param_autosave = false ;
need_param_autosave_timeout = 0 ;
2015-03-28 13:06:05 -07:00
} else {
2015-04-03 16:14:04 +02:00
need_param_autosave_timeout = hrt_absolute_time ( ) ;
2015-03-28 13:06:05 -07:00
}
}
} else if ( pret < 0 ) {
2013-08-17 18:39:46 +02:00
/* this is undesirable but not much we can do - might want to flag unhappy status */
2016-02-05 00:54:19 +01:00
warn ( " commander: poll error %d, %d " , pret , errno ) ;
2013-08-17 18:39:46 +02:00
continue ;
2015-03-28 13:06:05 -07:00
} else {
2013-08-07 20:21:49 +02:00
2015-03-28 13:06:05 -07:00
/* if we reach here, we have a valid command */
orb_copy ( ORB_ID ( vehicle_command ) , cmd_sub , & cmd ) ;
2013-03-25 14:53:54 -07:00
2016-02-17 16:50:13 +01:00
/* ignore commands the high-prio loop or the navigator handles */
2015-05-26 22:55:14 -07:00
if ( cmd . command = = vehicle_command_s : : VEHICLE_CMD_DO_SET_MODE | |
cmd . command = = vehicle_command_s : : VEHICLE_CMD_COMPONENT_ARM_DISARM | |
cmd . command = = vehicle_command_s : : VEHICLE_CMD_NAV_TAKEOFF | |
2016-02-17 16:50:13 +01:00
cmd . command = = vehicle_command_s : : VEHICLE_CMD_DO_SET_SERVO | |
cmd . command = = vehicle_command_s : : VEHICLE_CMD_DO_CHANGE_SPEED ) {
2015-03-28 13:06:05 -07:00
continue ;
}
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
/* only handle low-priority commands here */
switch ( cmd . command ) {
2013-08-07 20:21:49 +02:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN :
2015-03-28 13:06:05 -07:00
if ( is_safe ( & status , & safety , & armed ) ) {
if ( ( ( int ) ( cmd . param1 ) ) = = 1 ) {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
usleep ( 100000 ) ;
/* reboot */
2015-05-06 14:43:11 -07:00
px4_systemreset ( false ) ;
2013-08-22 15:57:17 +02:00
2015-03-28 13:06:05 -07:00
} else if ( ( ( int ) ( cmd . param1 ) ) = = 3 ) {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
usleep ( 100000 ) ;
/* reboot to bootloader */
2015-05-06 14:43:11 -07:00
px4_systemreset ( true ) ;
2013-08-27 23:08:00 +02:00
2015-03-28 13:06:05 -07:00
} else {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
}
2013-08-27 23:08:00 +02:00
2013-08-17 18:39:46 +02:00
} else {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED , command_ack_pub , command_ack ) ;
2013-08-17 18:39:46 +02:00
}
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
break ;
2013-08-27 23:08:00 +02:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_CALIBRATION : {
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
int calib_ret = ERROR ;
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
/* try to go to INIT/PREFLIGHT arming state */
2016-02-24 08:00:33 +00:00
if ( TRANSITION_DENIED = = arming_state_transition ( & status ,
2016-04-07 16:19:20 +02:00
& battery ,
2016-02-24 08:00:33 +00:00
& safety ,
vehicle_status_s : : ARMING_STATE_INIT ,
& armed ,
false /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ) {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
break ;
2015-05-21 17:25:37 +02:00
} else {
2016-02-25 17:00:39 +00:00
status_flags . condition_calibration_enabled = true ;
2015-03-28 13:06:05 -07:00
}
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
if ( ( int ) ( cmd . param1 ) = = 1 ) {
/* gyro calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_gyro_calibration ( & mavlink_log_pub ) ;
2013-03-25 14:53:54 -07:00
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param2 ) = = 1 ) {
/* magnetometer calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_mag_calibration ( & mavlink_log_pub ) ;
2013-08-22 15:57:17 +02:00
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param3 ) = = 1 ) {
/* zero-altitude pressure calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_DENIED , command_ack_pub , command_ack ) ;
2013-08-22 15:57:17 +02:00
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param4 ) = = 1 ) {
/* RC calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
/* disable RC control input completely */
2016-02-26 11:01:12 +00:00
status_flags . rc_input_blocked = true ;
2015-03-28 13:06:05 -07:00
calib_ret = OK ;
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " CAL: Disabling RC IN " ) ;
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param4 ) = = 2 ) {
/* RC trim calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_trim_calibration ( & mavlink_log_pub ) ;
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param5 ) = = 1 ) {
/* accelerometer calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_accel_calibration ( & mavlink_log_pub ) ;
2015-05-19 14:20:00 +02:00
} else if ( ( int ) ( cmd . param5 ) = = 2 ) {
// board offset calibration
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_level_calibration ( & mavlink_log_pub ) ;
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param6 ) = = 1 ) {
/* airspeed calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_airspeed_calibration ( & mavlink_log_pub ) ;
2015-03-28 13:06:05 -07:00
2015-04-28 14:54:58 +02:00
} else if ( ( int ) ( cmd . param7 ) = = 1 ) {
/* do esc calibration */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2016-03-15 18:25:02 +00:00
calib_ret = do_esc_calibration ( & mavlink_log_pub , & armed ) ;
2016-02-12 21:39:50 -08:00
2015-03-28 13:06:05 -07:00
} else if ( ( int ) ( cmd . param4 ) = = 0 ) {
/* RC calibration ended - have we been in one worth confirming? */
2016-02-26 11:01:12 +00:00
if ( status_flags . rc_input_blocked ) {
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2015-03-28 13:06:05 -07:00
/* enable RC control input */
2016-02-26 11:01:12 +00:00
status_flags . rc_input_blocked = false ;
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " CAL: Re-enabling RC IN " ) ;
2015-05-21 17:25:37 +02:00
calib_ret = OK ;
2015-03-28 13:06:05 -07:00
}
2015-04-28 14:54:58 +02:00
/* this always succeeds */
calib_ret = OK ;
2014-02-01 13:21:51 +01:00
}
2016-02-25 17:00:39 +00:00
status_flags . condition_calibration_enabled = false ;
2015-05-21 17:25:37 +02:00
2015-03-28 13:06:05 -07:00
if ( calib_ret = = OK ) {
tune_positive ( true ) ;
2014-02-01 13:21:51 +01:00
2015-04-25 12:37:43 -07:00
// Update preflight check status
// we do not set the calibration return value based on it because the calibration
// might have worked just fine, but the preflight check fails for a different reason,
// so this would be prone to false negatives.
2013-03-25 14:53:54 -07:00
2015-04-25 12:37:43 -07:00
bool checkAirspeed = false ;
2015-11-10 19:33:14 +05:30
bool hotplug_timeout = hrt_elapsed_time ( & commander_boot_timestamp ) > HOTPLUG_SENS_TIMEOUT ;
2015-04-25 12:37:43 -07:00
/* Perform airspeed check only if circuit breaker is not
* engaged and it ' s not a rotary wing */
2016-02-25 17:00:39 +00:00
if ( ! status_flags . circuit_breaker_engaged_airspd_check & & ! status . is_rotary_wing ) {
2015-04-25 12:37:43 -07:00
checkAirspeed = true ;
}
2015-04-19 23:07:32 +02:00
2016-02-25 17:00:39 +00:00
status_flags . condition_system_sensors_initialized = Commander : : preflightCheck ( & mavlink_log_pub , true , true , true , true , checkAirspeed ,
2016-07-12 12:12:59 +02:00
! ( status . rc_input_mode > = vehicle_status_s : : RC_IN_MODE_OFF ) , ! can_arm_without_gps , /* checkDynamic */ true , hotplug_timeout ) ;
2016-02-24 08:00:33 +00:00
arming_state_transition ( & status ,
2016-04-07 16:19:20 +02:00
& battery ,
2016-02-24 08:00:33 +00:00
& safety ,
vehicle_status_s : : ARMING_STATE_STANDBY ,
& armed ,
false /* fRunPreArmChecks */ ,
& mavlink_log_pub ,
2016-02-26 11:01:12 +00:00
& status_flags ,
2016-06-07 16:00:23 +02:00
avionics_power_rail_voltage ,
can_arm_without_gps ) ;
2015-03-08 14:51:23 +01:00
2015-04-25 12:37:43 -07:00
} else {
tune_negative ( true ) ;
}
2014-05-11 13:36:51 +02:00
2015-03-28 13:06:05 -07:00
break ;
2014-05-11 13:36:51 +02:00
}
2013-03-25 14:53:54 -07:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_PREFLIGHT_STORAGE : {
2015-04-19 23:07:32 +02:00
2015-03-28 13:06:05 -07:00
if ( ( ( int ) ( cmd . param1 ) ) = = 0 ) {
int ret = param_load_default ( ) ;
2013-07-28 23:12:16 +04:00
2015-03-28 13:06:05 -07:00
if ( ret = = OK ) {
2016-03-15 18:25:02 +00:00
mavlink_log_info ( & mavlink_log_pub , " settings loaded " ) ;
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2013-07-28 23:12:16 +04:00
2015-03-28 13:06:05 -07:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " settings load ERROR " ) ;
2013-09-14 08:55:45 +02:00
2015-03-28 13:06:05 -07:00
/* convenience as many parts of NuttX use negative errno */
if ( ret < 0 ) {
ret = - ret ;
}
2013-08-17 18:39:46 +02:00
2015-03-28 13:06:05 -07:00
if ( ret < 1000 ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " ERROR: %s " , strerror ( ret ) ) ;
2015-03-28 13:06:05 -07:00
}
2013-09-14 08:55:45 +02:00
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_FAILED , command_ack_pub , command_ack ) ;
2014-05-11 13:36:51 +02:00
}
2013-09-05 13:24:21 +02:00
2015-03-28 13:06:05 -07:00
} else if ( ( ( int ) ( cmd . param1 ) ) = = 1 ) {
2015-04-25 12:53:58 +02:00
2016-04-05 12:34:40 +02:00
# ifdef __PX4_QURT
// TODO FIXME: on snapdragon the save happens to early when the params
// are not set yet. We therefore need to wait some time first.
usleep ( 1000000 ) ;
# endif
2015-03-28 13:06:05 -07:00
int ret = param_save_default ( ) ;
2013-09-14 08:55:45 +02:00
2015-03-28 13:06:05 -07:00
if ( ret = = OK ) {
2015-04-25 12:53:58 +02:00
if ( need_param_autosave ) {
need_param_autosave = false ;
need_param_autosave_timeout = 0 ;
}
2015-05-14 17:33:07 +02:00
/* do not spam MAVLink, but provide the answer / green led mechanism */
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2013-08-17 18:39:46 +02:00
2015-03-28 13:06:05 -07:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " settings save error " ) ;
2013-09-14 08:55:45 +02:00
2015-03-28 13:06:05 -07:00
/* convenience as many parts of NuttX use negative errno */
if ( ret < 0 ) {
ret = - ret ;
}
2013-08-17 18:39:46 +02:00
2015-03-28 13:06:05 -07:00
if ( ret < 1000 ) {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " ERROR: %s " , strerror ( ret ) ) ;
2015-03-28 13:06:05 -07:00
}
2013-09-14 08:55:45 +02:00
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_FAILED , command_ack_pub , command_ack ) ;
2015-08-08 00:08:14 +02:00
}
} else if ( ( ( int ) ( cmd . param1 ) ) = = 2 ) {
/* reset parameters and save empty file */
param_reset_all ( ) ;
int ret = param_save_default ( ) ;
if ( ret = = OK ) {
/* do not spam MAVLink, but provide the answer / green led mechanism */
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " onboard parameters reset " ) ;
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_ACCEPTED , command_ack_pub , command_ack ) ;
2015-08-08 00:08:14 +02:00
} else {
2016-03-15 18:25:02 +00:00
mavlink_log_critical ( & mavlink_log_pub , " param reset error " ) ;
2015-12-12 13:01:49 +01:00
answer_command ( cmd , vehicle_command_s : : VEHICLE_CMD_RESULT_FAILED , command_ack_pub , command_ack ) ;
2014-05-11 13:36:51 +02:00
}
2013-08-27 23:08:00 +02:00
}
2015-03-28 13:06:05 -07:00
break ;
2013-08-17 18:39:46 +02:00
}
2013-08-27 23:08:00 +02:00
2015-05-26 22:55:14 -07:00
case vehicle_command_s : : VEHICLE_CMD_START_RX_PAIR :
2015-03-28 13:06:05 -07:00
/* handled in the IO driver */
2013-08-27 23:08:00 +02:00
break ;
2013-08-17 18:39:46 +02:00
2015-03-28 13:06:05 -07:00
default :
/* don't answer on unsupported commands, it will be done in main loop */
break ;
2015-03-23 10:52:32 -07:00
}
2013-08-17 18:39:46 +02:00
}
2013-03-25 14:53:54 -07:00
}
2015-07-01 11:05:45 -07:00
px4_close ( cmd_sub ) ;
2013-09-01 10:29:30 +02:00
2013-09-08 20:05:15 +02:00
return NULL ;
2013-03-25 14:53:54 -07:00
}