2012-08-04 19:12:36 -03:00
/****************************************************************************
*
* Copyright ( C ) 2012 PX4 Development Team . All rights reserved .
2012-10-23 08:15:36 -03:00
* Author : Petri Tanskanen < petri . tanskanen @ inf . ethz . ch >
* Lorenz Meier < lm @ inf . ethz . ch >
* Thomas Gubler < thomasgubler @ student . ethz . ch >
* Julian Oes < joes @ student . ethz . ch >
2012-08-04 19:12:36 -03: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 .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
* @ file commander . c
* Main system state machine implementation .
2012-10-23 08:15:36 -03:00
*
* @ author Petri Tanskanen < petri . tanskanen @ inf . ethz . ch >
* @ author Lorenz Meier < lm @ inf . ethz . ch >
* @ author Thomas Gubler < thomasgubler @ student . ethz . ch >
* @ author Julian Oes < joes @ student . ethz . ch >
*
2012-08-04 19:12:36 -03:00
*/
# include "commander.h"
# include <nuttx/config.h>
# include <pthread.h>
# include <stdio.h>
# include <stdlib.h>
# include <stdbool.h>
# include <string.h>
# include <unistd.h>
# include <fcntl.h>
# include <errno.h>
# include <debug.h>
# include <sys/prctl.h>
# include <v1.0/common/mavlink.h>
# include <string.h>
# include <arch/board/drv_led.h>
2012-10-23 22:02:36 -03:00
# include <drivers/drv_hrt.h>
# include <drivers/drv_hrt.h>
2012-10-21 21:51:21 -03:00
# include <drivers/drv_tone_alarm.h>
2012-08-04 19:12:36 -03:00
# include "state_machine_helper.h"
# include "systemlib/systemlib.h"
# include <math.h>
# include <poll.h>
# include <uORB/uORB.h>
# include <uORB/topics/sensor_combined.h>
2012-09-21 07:55:41 -03:00
# include <uORB/topics/manual_control_setpoint.h>
# include <uORB/topics/offboard_control_setpoint.h>
2012-08-04 19:12:36 -03:00
# include <uORB/topics/vehicle_gps_position.h>
# include <uORB/topics/vehicle_command.h>
2012-08-23 19:01:23 -03:00
# include <uORB/topics/subsystem_info.h>
2012-09-05 06:37:17 -03:00
# include <uORB/topics/actuator_controls.h>
2012-08-04 19:12:36 -03:00
# include <mavlink/mavlink_log.h>
2012-09-25 05:31:19 -03:00
2012-08-20 18:52:13 -03:00
# include <systemlib/param/param.h>
2012-08-04 19:12:36 -03:00
# include <systemlib/systemlib.h>
2012-09-11 18:35:01 -03:00
# include <systemlib/err.h>
/* XXX MOVE CALIBRATION TO SENSORS APP THREAD */
# include <drivers/drv_accel.h>
# include <drivers/drv_gyro.h>
# include <drivers/drv_mag.h>
# include <drivers/drv_baro.h>
2012-10-21 10:36:29 -03:00
# include "calibration_routines.h"
2012-09-11 18:35:01 -03:00
2012-09-21 07:55:41 -03:00
PARAM_DEFINE_INT32 ( SYS_FAILSAVE_LL , 0 ) ; /**< Go into low-level failsafe after 0 ms */
//PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */
2012-08-04 19:12:36 -03:00
2012-10-24 01:43:41 -03:00
# include <systemlib/cpuload.h>
2012-08-04 19:12:36 -03:00
extern struct system_load_s system_load ;
/* Decouple update interval and hysteris counters, all depends on intervals */
# define COMMANDER_MONITORING_INTERVAL 50000
# define COMMANDER_MONITORING_LOOPSPERMSEC (1 / (COMMANDER_MONITORING_INTERVAL / 1000.0f))
# define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
# define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
2012-09-21 07:55:41 -03:00
# define STICK_ON_OFF_LIMIT 0.75f
# define STICK_THRUST_RANGE 1.0f
2012-08-04 19:12:36 -03:00
# define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
# define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
# define GPS_FIX_TYPE_2D 2
# define GPS_FIX_TYPE_3D 3
2012-09-21 07:55:41 -03:00
# define GPS_QUALITY_GOOD_HYSTERIS_TIME_MS 5000
# define GPS_QUALITY_GOOD_COUNTER_LIMIT (GPS_QUALITY_GOOD_HYSTERIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
2012-08-04 19:12:36 -03:00
/* File descriptors */
static int leds ;
static int buzzer ;
static int mavlink_fd ;
static bool commander_initialized = false ;
2012-08-18 11:48:43 -03:00
static struct vehicle_status_s current_status ; /**< Main state machine */
2012-08-22 03:44:22 -03:00
static orb_advert_t stat_pub ;
2012-08-04 19:12:36 -03:00
2012-10-15 03:52:41 -03:00
// static uint16_t nofix_counter = 0;
// static uint16_t gotfix_counter = 0;
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
static unsigned int failsafe_lowlevel_timeout_ms ;
2012-10-23 08:15:36 -03:00
static bool thread_should_exit = false ; /**< daemon exit flag */
static bool thread_running = false ; /**< daemon status flag */
static int daemon_task ; /**< Handle of daemon task / thread */
2012-08-04 19:12:36 -03:00
/* pthread loops */
2012-08-23 19:01:23 -03:00
static void * orb_receive_loop ( void * arg ) ;
2012-08-04 19:12:36 -03:00
__EXPORT int commander_main ( int argc , char * argv [ ] ) ;
2012-08-20 18:52:13 -03:00
/**
* Mainloop of commander .
*/
int commander_thread_main ( int argc , char * argv [ ] ) ;
2012-08-04 19:12:36 -03:00
static int buzzer_init ( void ) ;
static void buzzer_deinit ( void ) ;
2012-10-22 08:58:13 -03:00
static void tune_confirm ( ) ;
2012-08-20 18:52:13 -03:00
static int led_init ( void ) ;
static void led_deinit ( void ) ;
static int led_toggle ( int led ) ;
static int led_on ( int led ) ;
static int led_off ( int led ) ;
2012-09-25 05:31:19 -03:00
static int pm_save_eeprom ( bool only_unsaved ) ;
2012-08-27 17:57:20 -03:00
static void do_gyro_calibration ( int status_pub , struct vehicle_status_s * status ) ;
static void do_mag_calibration ( int status_pub , struct vehicle_status_s * status ) ;
2012-08-29 09:20:55 -03:00
static void do_accel_calibration ( int status_pub , struct vehicle_status_s * status ) ;
2012-08-20 18:52:13 -03:00
static void handle_command ( int status_pub , struct vehicle_status_s * current_status , struct vehicle_command_s * cmd ) ;
int trigger_audio_alarm ( uint8_t old_mode , uint8_t old_state , uint8_t new_mode , uint8_t new_state ) ;
/**
* Print the correct usage .
*/
static void usage ( const char * reason ) ;
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
/**
* Sort calibration values .
*
* Sorts the calibration values with bubble sort .
*
* @ param a The array to sort
* @ param n The number of entries in the array
*/
2012-10-15 03:52:41 -03:00
// static void cal_bsort(float a[], int n);
2012-08-23 19:01:23 -03:00
2012-08-04 19:12:36 -03:00
static int buzzer_init ( )
{
buzzer = open ( " /dev/tone_alarm " , O_WRONLY ) ;
if ( buzzer < 0 ) {
fprintf ( stderr , " [commander] Buzzer: open fail \n " ) ;
return ERROR ;
}
return 0 ;
}
static void buzzer_deinit ( )
{
close ( buzzer ) ;
}
static int led_init ( )
{
leds = open ( " /dev/led " , O_RDONLY | O_NONBLOCK ) ;
if ( leds < 0 ) {
fprintf ( stderr , " [commander] LED: open fail \n " ) ;
return ERROR ;
}
if ( ioctl ( leds , LED_ON , LED_BLUE ) | | ioctl ( leds , LED_ON , LED_AMBER ) ) {
fprintf ( stderr , " [commander] LED: ioctl fail \n " ) ;
return ERROR ;
}
return 0 ;
}
static void led_deinit ( )
{
close ( leds ) ;
}
static int led_toggle ( int led )
{
static int last_blue = LED_ON ;
static int last_amber = LED_ON ;
if ( led = = LED_BLUE ) last_blue = ( last_blue = = LED_ON ) ? LED_OFF : LED_ON ;
if ( led = = LED_AMBER ) last_amber = ( last_amber = = LED_ON ) ? LED_OFF : LED_ON ;
return ioctl ( leds , ( ( led = = LED_BLUE ) ? last_blue : last_amber ) , led ) ;
}
static int led_on ( int led )
{
return ioctl ( leds , LED_ON , led ) ;
}
static int led_off ( int led )
{
return ioctl ( leds , LED_OFF , led ) ;
}
enum AUDIO_PATTERN {
AUDIO_PATTERN_ERROR = 1 ,
AUDIO_PATTERN_NOTIFY_POSITIVE = 2 ,
AUDIO_PATTERN_NOTIFY_NEUTRAL = 3 ,
AUDIO_PATTERN_NOTIFY_NEGATIVE = 4 ,
AUDIO_PATTERN_TETRIS = 5
} ;
int trigger_audio_alarm ( uint8_t old_mode , uint8_t old_state , uint8_t new_mode , uint8_t new_state ) {
/* Trigger alarm if going into any error state */
if ( ( ( new_state = = SYSTEM_STATE_GROUND_ERROR ) & & ( old_state ! = SYSTEM_STATE_GROUND_ERROR ) ) | |
( ( new_state = = SYSTEM_STATE_MISSION_ABORT ) & & ( old_state ! = SYSTEM_STATE_MISSION_ABORT ) ) ) {
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
ioctl ( buzzer , TONE_SET_ALARM , AUDIO_PATTERN_ERROR ) ;
}
/* Trigger neutral on arming / disarming */
if ( ( ( new_state = = SYSTEM_STATE_GROUND_READY ) & & ( old_state ! = SYSTEM_STATE_GROUND_READY ) ) ) {
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
ioctl ( buzzer , TONE_SET_ALARM , AUDIO_PATTERN_NOTIFY_NEUTRAL ) ;
}
/* Trigger Tetris on being bored */
return 0 ;
}
2012-10-22 08:58:13 -03:00
void tune_confirm ( ) {
ioctl ( buzzer , TONE_SET_ALARM , 3 ) ;
}
2012-09-25 05:31:19 -03:00
static const char * parameter_file = " /eeprom/parameters " ;
static int pm_save_eeprom ( bool only_unsaved )
{
/* delete the file in case it exists */
unlink ( parameter_file ) ;
/* create the file */
int fd = open ( parameter_file , O_WRONLY | O_CREAT | O_EXCL ) ;
if ( fd < 0 ) {
warn ( " opening '%s' for writing failed " , parameter_file ) ;
return - 1 ;
}
int result = param_export ( fd , only_unsaved ) ;
close ( fd ) ;
if ( result ! = 0 ) {
unlink ( parameter_file ) ;
warn ( " error exporting parameters to '%s' " , parameter_file ) ;
return - 2 ;
}
return 0 ;
}
2012-08-13 13:53:37 -03:00
void do_mag_calibration ( int status_pub , struct vehicle_status_s * status )
2012-08-05 17:51:31 -03:00
{
2012-08-06 18:43:09 -03:00
/* set to mag calibration mode */
2012-08-29 09:20:55 -03:00
status - > flag_preflight_mag_calibration = true ;
2012-08-13 13:53:37 -03:00
state_machine_publish ( status_pub , status , mavlink_fd ) ;
2012-08-06 18:43:09 -03:00
2012-10-21 10:36:29 -03:00
int sub_mag = orb_subscribe ( ORB_ID ( sensor_mag ) ) ;
struct mag_report mag ;
2012-08-05 17:51:31 -03:00
2012-10-22 03:14:43 -03:00
/* 45 seconds */
2012-10-17 10:09:28 -03:00
uint64_t calibration_interval = 45 * 1000 * 1000 ;
2012-10-22 03:14:43 -03:00
/* maximum 2000 values */
const unsigned int calibration_maxcount = 2000 ;
2012-08-05 17:51:31 -03:00
unsigned int calibration_counter = 0 ;
2012-10-22 03:14:43 -03:00
/* limit update rate to get equally spaced measurements over time (in ms) */
orb_set_interval ( sub_mag , ( calibration_interval / 1000 ) / calibration_maxcount ) ;
// XXX old cal
// * FLT_MIN is not the most negative float number,
// * but the smallest number by magnitude float can
// * represent. Use -FLT_MAX to initialize the most
// * negative number
// float mag_max[3] = {-FLT_MAX, -FLT_MAX, -FLT_MAX};
// float mag_min[3] = {FLT_MAX, FLT_MAX, FLT_MAX};
2012-08-08 13:47:46 -03:00
2012-10-22 03:14:43 -03:00
int fd = open ( MAG_DEVICE_PATH , O_RDONLY ) ;
2012-10-17 03:02:50 -03:00
2012-10-21 10:36:29 -03:00
/* erase old calibration */
2012-09-11 18:35:01 -03:00
struct mag_scale mscale_null = {
0.0f ,
1.0f ,
0.0f ,
1.0f ,
0.0f ,
1.0f ,
} ;
2012-10-15 03:52:41 -03:00
if ( OK ! = ioctl ( fd , MAGIOCSSCALE , ( long unsigned int ) & mscale_null ) ) {
2012-09-11 18:35:01 -03:00
warn ( " WARNING: failed to set scale / offsets for mag " ) ;
2012-10-15 03:52:41 -03:00
mavlink_log_info ( mavlink_fd , " [commander] failed to set scale / offsets for mag " ) ;
}
2012-10-21 10:36:29 -03:00
/* calibrate range */
if ( OK ! = ioctl ( fd , MAGIOCCALIBRATE , fd ) ) {
warnx ( " failed to calibrate scale " ) ;
}
2012-09-11 18:35:01 -03:00
close ( fd ) ;
2012-10-21 10:36:29 -03:00
/* calibrate offsets */
2012-10-22 03:14:43 -03:00
// uint64_t calibration_start = hrt_absolute_time();
2012-10-15 03:52:41 -03:00
uint64_t axis_deadline = hrt_absolute_time ( ) ;
uint64_t calibration_deadline = hrt_absolute_time ( ) + calibration_interval ;
2012-10-17 13:27:49 -03:00
const char axislabels [ 3 ] = { ' Z ' , ' X ' , ' Y ' } ;
int axis_index = - 1 ;
2012-10-15 03:52:41 -03:00
2012-10-21 10:36:29 -03:00
float * x = malloc ( sizeof ( float ) * calibration_maxcount ) ;
float * y = malloc ( sizeof ( float ) * calibration_maxcount ) ;
float * z = malloc ( sizeof ( float ) * calibration_maxcount ) ;
2012-10-29 12:41:53 -03:00
tune_confirm ( ) ;
sleep ( 2 ) ;
tune_confirm ( ) ;
2012-10-21 10:36:29 -03:00
while ( hrt_absolute_time ( ) < calibration_deadline & &
calibration_counter < calibration_maxcount ) {
2012-08-05 17:51:31 -03:00
/* wait blocking for new data */
2012-10-21 10:36:29 -03:00
struct pollfd fds [ 1 ] = { { . fd = sub_mag , . events = POLLIN } } ;
2012-08-05 17:51:31 -03:00
2012-10-15 03:52:41 -03:00
/* user guidance */
2012-10-17 13:27:49 -03:00
if ( hrt_absolute_time ( ) > = axis_deadline & &
2012-10-15 03:52:41 -03:00
axis_index < 3 ) {
2012-10-17 13:27:49 -03:00
axis_index + + ;
2012-10-15 03:52:41 -03:00
char buf [ 50 ] ;
sprintf ( buf , " [commander] Please rotate around %c " , axislabels [ axis_index ] ) ;
mavlink_log_info ( mavlink_fd , buf ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-10-15 03:52:41 -03:00
axis_deadline + = calibration_interval / 3 ;
}
2012-10-15 19:02:53 -03:00
if ( ! ( axis_index < 3 ) ) {
2012-10-17 10:09:28 -03:00
break ;
2012-10-15 19:02:53 -03:00
}
2012-10-15 03:52:41 -03:00
// int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
// if ((axis_left / 1000) == 0 && axis_left > 0) {
// char buf[50];
// sprintf(buf, "[commander] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
// mavlink_log_info(mavlink_fd, buf);
// }
2012-08-05 17:51:31 -03:00
if ( poll ( fds , 1 , 1000 ) ) {
2012-10-21 10:36:29 -03:00
orb_copy ( ORB_ID ( sensor_mag ) , sub_mag , & mag ) ;
x [ calibration_counter ] = mag . x ;
y [ calibration_counter ] = mag . y ;
z [ calibration_counter ] = mag . z ;
2012-08-05 17:51:31 -03:00
/* get min/max values */
2012-10-21 10:36:29 -03:00
// if (mag.x < mag_min[0]) {
// mag_min[0] = mag.x;
// }
// else if (mag.x > mag_max[0]) {
// mag_max[0] = mag.x;
// }
// if (raw.magnetometer_ga[1] < mag_min[1]) {
// mag_min[1] = raw.magnetometer_ga[1];
// }
// else if (raw.magnetometer_ga[1] > mag_max[1]) {
// mag_max[1] = raw.magnetometer_ga[1];
// }
// if (raw.magnetometer_ga[2] < mag_min[2]) {
// mag_min[2] = raw.magnetometer_ga[2];
// }
// else if (raw.magnetometer_ga[2] > mag_max[2]) {
// mag_max[2] = raw.magnetometer_ga[2];
// }
2012-08-05 17:51:31 -03:00
calibration_counter + + ;
} else {
/* any poll failure for 1s is a reason to abort */
2012-10-04 11:01:42 -03:00
mavlink_log_info ( mavlink_fd , " [commander] mag cal canceled " ) ;
2012-09-27 11:50:20 -03:00
break ;
2012-08-05 17:51:31 -03:00
}
}
2012-08-04 19:12:36 -03:00
2012-10-21 10:36:29 -03:00
float sphere_x ;
float sphere_y ;
float sphere_z ;
float sphere_radius ;
sphere_fit_least_squares ( x , y , z , calibration_counter , 100 , 0.0f , & sphere_x , & sphere_y , & sphere_z , & sphere_radius ) ;
free ( x ) ;
free ( y ) ;
free ( z ) ;
2012-10-22 03:14:43 -03:00
if ( isfinite ( sphere_x ) & & isfinite ( sphere_y ) & & isfinite ( sphere_z ) ) {
2012-08-17 12:37:58 -03:00
2012-10-21 10:36:29 -03:00
fd = open ( MAG_DEVICE_PATH , 0 ) ;
2012-08-29 09:20:55 -03:00
2012-10-21 10:36:29 -03:00
struct mag_scale mscale ;
if ( OK ! = ioctl ( fd , MAGIOCGSCALE , ( long unsigned int ) & mscale ) )
warn ( " WARNING: failed to get scale / offsets for mag " ) ;
2012-10-22 03:14:43 -03:00
mscale . x_offset = sphere_x ;
mscale . y_offset = sphere_y ;
mscale . z_offset = sphere_z ;
2012-10-21 10:36:29 -03:00
if ( OK ! = ioctl ( fd , MAGIOCSSCALE , ( long unsigned int ) & mscale ) )
warn ( " WARNING: failed to set scale / offsets for mag " ) ;
close ( fd ) ;
2012-08-29 09:20:55 -03:00
2012-10-15 03:52:41 -03:00
/* announce and set new offset */
2012-09-25 11:36:33 -03:00
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_XOFF " ) , & ( mscale . x_offset ) ) ) {
2012-10-15 03:52:41 -03:00
fprintf ( stderr , " [commander] Setting X mag offset failed! \n " ) ;
}
2012-09-25 11:36:33 -03:00
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_YOFF " ) , & ( mscale . y_offset ) ) ) {
2012-10-15 03:52:41 -03:00
fprintf ( stderr , " [commander] Setting Y mag offset failed! \n " ) ;
}
2012-08-05 17:51:31 -03:00
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_ZOFF " ) , & ( mscale . z_offset ) ) ) {
2012-10-15 03:52:41 -03:00
fprintf ( stderr , " [commander] Setting Z mag offset failed! \n " ) ;
}
2012-09-11 18:35:01 -03:00
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_XSCALE " ) , & ( mscale . x_scale ) ) ) {
fprintf ( stderr , " [commander] Setting X mag scale failed! \n " ) ;
2012-10-17 03:02:50 -03:00
}
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_YSCALE " ) , & ( mscale . y_scale ) ) ) {
fprintf ( stderr , " [commander] Setting Y mag scale failed! \n " ) ;
2012-10-17 03:02:50 -03:00
}
2012-10-21 10:36:29 -03:00
if ( param_set ( param_find ( " SENS_MAG_ZSCALE " ) , & ( mscale . z_scale ) ) ) {
fprintf ( stderr , " [commander] Setting Z mag scale failed! \n " ) ;
2012-10-17 03:02:50 -03:00
}
2012-10-15 03:52:41 -03:00
/* auto-save to EEPROM */
int save_ret = pm_save_eeprom ( false ) ;
if ( save_ret ! = 0 ) {
warn ( " WARNING: auto-save of params to EEPROM failed " ) ;
}
2012-10-21 10:36:29 -03:00
2012-10-22 03:14:43 -03:00
printf ( " [mag cal] \t scale: %.6f %.6f %.6f \n \t offset: %.6f %.6f %.6f \n radius: %.6f GA \n " ,
( double ) mscale . x_scale , ( double ) mscale . y_scale , ( double ) mscale . z_scale ,
( double ) mscale . x_offset , ( double ) mscale . y_offset , ( double ) mscale . z_offset , ( double ) sphere_radius ) ;
2012-10-15 03:52:41 -03:00
2012-10-22 03:14:43 -03:00
char buf [ 52 ] ;
sprintf ( buf , " mag off: x:%.2f y:%.2f z:%.2f Ga " , ( double ) mscale . x_offset ,
( double ) mscale . y_offset , ( double ) mscale . z_offset ) ;
mavlink_log_info ( mavlink_fd , buf ) ;
sprintf ( buf , " mag scale: x:%.2f y:%.2f z:%.2f " , ( double ) mscale . x_scale ,
( double ) mscale . y_scale , ( double ) mscale . z_scale ) ;
mavlink_log_info ( mavlink_fd , buf ) ;
2012-10-15 03:52:41 -03:00
mavlink_log_info ( mavlink_fd , " [commander] mag calibration done " ) ;
2012-10-29 12:41:53 -03:00
tune_confirm ( ) ;
sleep ( 2 ) ;
tune_confirm ( ) ;
sleep ( 2 ) ;
/* third beep by cal end routine */
2012-10-15 03:52:41 -03:00
} else {
mavlink_log_info ( mavlink_fd , " [commander] mag calibration FAILED (NaN) " ) ;
2012-09-25 05:31:19 -03:00
}
2012-10-21 10:36:29 -03:00
/* disable calibration mode */
status - > flag_preflight_mag_calibration = false ;
state_machine_publish ( status_pub , status , mavlink_fd ) ;
close ( sub_mag ) ;
2012-08-05 17:51:31 -03:00
}
2012-08-27 17:57:20 -03:00
void do_gyro_calibration ( int status_pub , struct vehicle_status_s * status )
2012-08-05 17:51:31 -03:00
{
2012-08-28 03:50:23 -03:00
/* set to gyro calibration mode */
2012-08-29 09:20:55 -03:00
status - > flag_preflight_gyro_calibration = true ;
2012-08-28 03:50:23 -03:00
state_machine_publish ( status_pub , status , mavlink_fd ) ;
2012-08-29 09:20:55 -03:00
const int calibration_count = 5000 ;
2012-08-04 19:12:36 -03:00
int sub_sensor_combined = orb_subscribe ( ORB_ID ( sensor_combined ) ) ;
struct sensor_combined_s raw ;
int calibration_counter = 0 ;
2012-08-05 17:51:31 -03:00
float gyro_offset [ 3 ] = { 0.0f , 0.0f , 0.0f } ;
2012-08-04 19:12:36 -03:00
2012-09-11 18:35:01 -03:00
/* set offsets to zero */
int fd = open ( GYRO_DEVICE_PATH , 0 ) ;
struct gyro_scale gscale_null = {
0.0f ,
1.0f ,
0.0f ,
1.0f ,
0.0f ,
1.0f ,
} ;
if ( OK ! = ioctl ( fd , GYROIOCSSCALE , ( long unsigned int ) & gscale_null ) )
warn ( " WARNING: failed to set scale / offsets for gyro " ) ;
close ( fd ) ;
2012-08-04 19:12:36 -03:00
while ( calibration_counter < calibration_count ) {
/* wait blocking for new data */
struct pollfd fds [ 1 ] = { { . fd = sub_sensor_combined , . events = POLLIN } } ;
if ( poll ( fds , 1 , 1000 ) ) {
orb_copy ( ORB_ID ( sensor_combined ) , sub_sensor_combined , & raw ) ;
2012-08-28 06:30:30 -03:00
gyro_offset [ 0 ] + = raw . gyro_rad_s [ 0 ] ;
gyro_offset [ 1 ] + = raw . gyro_rad_s [ 1 ] ;
gyro_offset [ 2 ] + = raw . gyro_rad_s [ 2 ] ;
2012-08-04 19:12:36 -03:00
calibration_counter + + ;
2012-08-05 17:51:31 -03:00
} else {
/* any poll failure for 1s is a reason to abort */
2012-09-27 11:50:20 -03:00
mavlink_log_info ( mavlink_fd , " [commander] gyro calibration aborted, retry " ) ;
2012-08-05 17:51:31 -03:00
return ;
2012-08-04 19:12:36 -03:00
}
}
gyro_offset [ 0 ] = gyro_offset [ 0 ] / calibration_count ;
gyro_offset [ 1 ] = gyro_offset [ 1 ] / calibration_count ;
gyro_offset [ 2 ] = gyro_offset [ 2 ] / calibration_count ;
2012-10-15 03:52:41 -03:00
/* exit gyro calibration mode */
status - > flag_preflight_gyro_calibration = false ;
state_machine_publish ( status_pub , status , mavlink_fd ) ;
2012-08-04 19:12:36 -03:00
2012-10-15 03:52:41 -03:00
if ( isfinite ( gyro_offset [ 0 ] ) & & isfinite ( gyro_offset [ 1 ] ) & & isfinite ( gyro_offset [ 2 ] ) ) {
2012-09-11 18:35:01 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_GYRO_XOFF " ) , & ( gyro_offset [ 0 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting X gyro offset failed! " ) ;
}
if ( param_set ( param_find ( " SENS_GYRO_YOFF " ) , & ( gyro_offset [ 1 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Y gyro offset failed! " ) ;
}
2012-09-25 05:31:19 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_GYRO_ZOFF " ) , & ( gyro_offset [ 2 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Z gyro offset failed! " ) ;
}
2012-08-28 03:50:23 -03:00
2012-10-15 03:52:41 -03:00
/* set offsets to actual value */
fd = open ( GYRO_DEVICE_PATH , 0 ) ;
struct gyro_scale gscale = {
gyro_offset [ 0 ] ,
1.0f ,
gyro_offset [ 1 ] ,
1.0f ,
gyro_offset [ 2 ] ,
1.0f ,
} ;
if ( OK ! = ioctl ( fd , GYROIOCSSCALE , ( long unsigned int ) & gscale ) )
warn ( " WARNING: failed to set scale / offsets for gyro " ) ;
close ( fd ) ;
/* auto-save to EEPROM */
int save_ret = pm_save_eeprom ( false ) ;
if ( save_ret ! = 0 ) {
warn ( " WARNING: auto-save of params to EEPROM failed " ) ;
}
2012-09-25 05:51:13 -03:00
2012-10-15 03:52:41 -03:00
// char buf[50];
// sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
// mavlink_log_info(mavlink_fd, buf);
mavlink_log_info ( mavlink_fd , " [commander] gyro calibration done " ) ;
2012-10-29 12:41:53 -03:00
tune_confirm ( ) ;
sleep ( 2 ) ;
tune_confirm ( ) ;
sleep ( 2 ) ;
/* third beep by cal end routine */
2012-10-15 03:52:41 -03:00
} else {
mavlink_log_info ( mavlink_fd , " [commander] gyro calibration FAILED (NaN) " ) ;
}
2012-08-04 19:12:36 -03:00
close ( sub_sensor_combined ) ;
}
2012-08-29 09:20:55 -03:00
void do_accel_calibration ( int status_pub , struct vehicle_status_s * status )
{
/* announce change */
2012-09-27 11:50:20 -03:00
mavlink_log_info ( mavlink_fd , " [commander] keep it level and still " ) ;
2012-08-29 09:20:55 -03:00
/* set to accel calibration mode */
status - > flag_preflight_accel_calibration = true ;
state_machine_publish ( status_pub , status , mavlink_fd ) ;
2012-10-10 12:47:28 -03:00
const int calibration_count = 2500 ;
2012-08-29 09:20:55 -03:00
int sub_sensor_combined = orb_subscribe ( ORB_ID ( sensor_combined ) ) ;
struct sensor_combined_s raw ;
int calibration_counter = 0 ;
float accel_offset [ 3 ] = { 0.0f , 0.0f , 0.0f } ;
2012-09-11 18:35:01 -03:00
int fd = open ( ACCEL_DEVICE_PATH , 0 ) ;
struct accel_scale ascale_null = {
0.0f ,
1.0f ,
0.0f ,
1.0f ,
0.0f ,
1.0f ,
} ;
if ( OK ! = ioctl ( fd , ACCELIOCSSCALE , ( long unsigned int ) & ascale_null ) )
warn ( " WARNING: failed to set scale / offsets for accel " ) ;
close ( fd ) ;
2012-08-29 09:20:55 -03:00
while ( calibration_counter < calibration_count ) {
/* wait blocking for new data */
struct pollfd fds [ 1 ] = { { . fd = sub_sensor_combined , . events = POLLIN } } ;
if ( poll ( fds , 1 , 1000 ) ) {
orb_copy ( ORB_ID ( sensor_combined ) , sub_sensor_combined , & raw ) ;
accel_offset [ 0 ] + = raw . accelerometer_m_s2 [ 0 ] ;
accel_offset [ 1 ] + = raw . accelerometer_m_s2 [ 1 ] ;
accel_offset [ 2 ] + = raw . accelerometer_m_s2 [ 2 ] ;
calibration_counter + + ;
} else {
/* any poll failure for 1s is a reason to abort */
2012-09-27 11:50:20 -03:00
mavlink_log_info ( mavlink_fd , " [commander] acceleration calibration aborted " ) ;
2012-08-29 09:20:55 -03:00
return ;
}
}
accel_offset [ 0 ] = accel_offset [ 0 ] / calibration_count ;
accel_offset [ 1 ] = accel_offset [ 1 ] / calibration_count ;
accel_offset [ 2 ] = accel_offset [ 2 ] / calibration_count ;
2012-10-15 03:52:41 -03:00
if ( isfinite ( accel_offset [ 0 ] ) & & isfinite ( accel_offset [ 1 ] ) & & isfinite ( accel_offset [ 2 ] ) ) {
/* add the removed length from x / y to z, since we induce a scaling issue else */
float total_len = sqrtf ( accel_offset [ 0 ] * accel_offset [ 0 ] + accel_offset [ 1 ] * accel_offset [ 1 ] + accel_offset [ 2 ] * accel_offset [ 2 ] ) ;
2012-08-29 09:20:55 -03:00
2012-10-15 03:52:41 -03:00
/* if length is correct, zero results here */
accel_offset [ 2 ] = accel_offset [ 2 ] + total_len ;
2012-08-29 09:20:55 -03:00
2012-10-15 03:52:41 -03:00
float scale = 9.80665f / total_len ;
2012-09-11 18:35:01 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_ACC_XOFF " ) , & ( accel_offset [ 0 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting X accel offset failed! " ) ;
}
if ( param_set ( param_find ( " SENS_ACC_YOFF " ) , & ( accel_offset [ 1 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Y accel offset failed! " ) ;
}
2012-08-29 09:20:55 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_ACC_ZOFF " ) , & ( accel_offset [ 2 ] ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Z accel offset failed! " ) ;
}
2012-08-29 09:20:55 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_ACC_XSCALE " ) , & ( scale ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting X accel offset failed! " ) ;
}
if ( param_set ( param_find ( " SENS_ACC_YSCALE " ) , & ( scale ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Y accel offset failed! " ) ;
}
2012-09-11 18:35:01 -03:00
2012-10-15 03:52:41 -03:00
if ( param_set ( param_find ( " SENS_ACC_ZSCALE " ) , & ( scale ) ) ) {
mavlink_log_critical ( mavlink_fd , " [commander] Setting Z accel offset failed! " ) ;
}
2012-09-11 18:35:01 -03:00
2012-10-15 03:52:41 -03:00
fd = open ( ACCEL_DEVICE_PATH , 0 ) ;
struct accel_scale ascale = {
accel_offset [ 0 ] ,
scale ,
accel_offset [ 1 ] ,
scale ,
accel_offset [ 2 ] ,
scale ,
} ;
if ( OK ! = ioctl ( fd , ACCELIOCSSCALE , ( long unsigned int ) & ascale ) )
warn ( " WARNING: failed to set scale / offsets for accel " ) ;
close ( fd ) ;
/* auto-save to EEPROM */
int save_ret = pm_save_eeprom ( false ) ;
if ( save_ret ! = 0 ) {
warn ( " WARNING: auto-save of params to EEPROM failed " ) ;
}
2012-09-11 18:35:01 -03:00
2012-10-15 03:52:41 -03:00
//char buf[50];
//sprintf(buf, "[commander] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
//mavlink_log_info(mavlink_fd, buf);
mavlink_log_info ( mavlink_fd , " [commander] accel calibration done " ) ;
2012-10-29 12:41:53 -03:00
tune_confirm ( ) ;
sleep ( 2 ) ;
tune_confirm ( ) ;
sleep ( 2 ) ;
/* third beep by cal end routine */
2012-10-15 03:52:41 -03:00
} else {
mavlink_log_info ( mavlink_fd , " [commander] accel calibration FAILED (NaN) " ) ;
2012-09-25 05:31:19 -03:00
}
2012-10-15 03:52:41 -03:00
/* exit accel calibration mode */
2012-08-29 09:20:55 -03:00
status - > flag_preflight_accel_calibration = false ;
state_machine_publish ( status_pub , status , mavlink_fd ) ;
2012-10-15 03:52:41 -03:00
2012-08-29 09:20:55 -03:00
close ( sub_sensor_combined ) ;
}
2012-08-04 19:12:36 -03:00
void handle_command ( int status_pub , struct vehicle_status_s * current_vehicle_status , struct vehicle_command_s * cmd )
{
/* result of the command */
uint8_t result = MAV_RESULT_UNSUPPORTED ;
2012-10-22 08:28:53 -03:00
/* announce command handling */
2012-10-29 12:41:53 -03:00
tune_confirm ( ) ;
2012-10-22 08:28:53 -03:00
2012-08-04 19:12:36 -03:00
/* supported command handling start */
/* request to set different system mode */
switch ( cmd - > command ) {
case MAV_CMD_DO_SET_MODE :
{
2012-08-13 13:53:37 -03:00
if ( OK = = update_state_machine_mode_request ( status_pub , current_vehicle_status , mavlink_fd , ( uint8_t ) cmd - > param1 ) ) {
2012-08-08 13:47:46 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_DENIED ;
}
}
break ;
2012-08-13 13:53:37 -03:00
case MAV_CMD_COMPONENT_ARM_DISARM : {
2012-08-08 13:47:46 -03:00
/* request to arm */
if ( ( int ) cmd - > param1 = = 1 ) {
2012-08-13 13:53:37 -03:00
if ( OK = = update_state_machine_mode_request ( status_pub , current_vehicle_status , mavlink_fd , VEHICLE_MODE_FLAG_SAFETY_ARMED ) ) {
2012-08-08 13:47:46 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_DENIED ;
}
/* request to disarm */
} else if ( ( int ) cmd - > param1 = = 0 ) {
2012-08-13 13:53:37 -03:00
if ( OK = = update_state_machine_mode_request ( status_pub , current_vehicle_status , mavlink_fd , VEHICLE_MODE_FLAG_SAFETY_ARMED ) ) {
2012-08-08 13:47:46 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_DENIED ;
}
}
}
break ;
/* request for an autopilot reboot */
2012-08-13 13:53:37 -03:00
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN : {
if ( ( int ) cmd - > param1 = = 1 ) {
if ( OK = = do_state_update ( status_pub , current_vehicle_status , mavlink_fd , SYSTEM_STATE_REBOOT ) ) {
/* SPECIAL CASE: SYSTEM WILL NEVER RETURN HERE */
result = MAV_RESULT_ACCEPTED ;
} else {
/* system may return here */
result = MAV_RESULT_DENIED ;
}
}
2012-08-04 19:12:36 -03:00
}
break ;
2012-08-13 13:53:37 -03:00
2012-09-19 13:53:29 -03:00
case PX4_CMD_CONTROLLER_SELECTION : {
bool changed = false ;
if ( ( int ) cmd - > param1 ! = ( int ) current_vehicle_status - > flag_control_rates_enabled ) {
current_vehicle_status - > flag_control_rates_enabled = cmd - > param1 ;
changed = true ;
}
if ( ( int ) cmd - > param2 ! = ( int ) current_vehicle_status - > flag_control_attitude_enabled ) {
current_vehicle_status - > flag_control_attitude_enabled = cmd - > param2 ;
changed = true ;
}
if ( ( int ) cmd - > param3 ! = ( int ) current_vehicle_status - > flag_control_velocity_enabled ) {
current_vehicle_status - > flag_control_velocity_enabled = cmd - > param3 ;
changed = true ;
}
if ( ( int ) cmd - > param4 ! = ( int ) current_vehicle_status - > flag_control_position_enabled ) {
current_vehicle_status - > flag_control_position_enabled = cmd - > param4 ;
changed = true ;
}
if ( changed ) {
/* publish current state machine */
state_machine_publish ( status_pub , current_vehicle_status , mavlink_fd ) ;
}
}
2012-08-04 19:12:36 -03:00
// /* request to land */
// case MAV_CMD_NAV_LAND:
// {
// //TODO: add check if landing possible
// //TODO: add landing maneuver
//
// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_ARMED)) {
// result = MAV_RESULT_ACCEPTED;
// } }
// break;
//
// /* request to takeoff */
// case MAV_CMD_NAV_TAKEOFF:
// {
// //TODO: add check if takeoff possible
// //TODO: add takeoff maneuver
//
// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_AUTO)) {
// result = MAV_RESULT_ACCEPTED;
// }
// }
// break;
//
/* preflight calibration */
2012-08-13 13:53:37 -03:00
case MAV_CMD_PREFLIGHT_CALIBRATION : {
2012-08-05 17:51:31 -03:00
bool handled = false ;
/* gyro calibration */
if ( ( int ) ( cmd - > param1 ) = = 1 ) {
2012-08-06 18:43:09 -03:00
/* transition to calibration state */
2012-08-13 13:53:37 -03:00
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_PREFLIGHT ) ;
2012-08-06 18:43:09 -03:00
if ( current_status . state_machine = = SYSTEM_STATE_PREFLIGHT ) {
2012-08-16 10:49:56 -03:00
mavlink_log_info ( mavlink_fd , " [commander] CMD starting gyro calibration " ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-06 18:43:09 -03:00
do_gyro_calibration ( status_pub , & current_status ) ;
2012-08-16 10:49:56 -03:00
mavlink_log_info ( mavlink_fd , " [commander] CMD finished gyro calibration " ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-13 13:53:37 -03:00
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_STANDBY ) ;
2012-08-06 18:43:09 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
2012-08-08 13:47:46 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] REJECTING gyro calibration " ) ;
2012-08-06 18:43:09 -03:00
result = MAV_RESULT_DENIED ;
}
2012-08-05 17:51:31 -03:00
handled = true ;
}
2012-08-04 19:12:36 -03:00
2012-08-05 17:51:31 -03:00
/* magnetometer calibration */
if ( ( int ) ( cmd - > param2 ) = = 1 ) {
2012-08-06 18:43:09 -03:00
/* transition to calibration state */
2012-08-13 13:53:37 -03:00
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_PREFLIGHT ) ;
2012-08-06 18:43:09 -03:00
if ( current_status . state_machine = = SYSTEM_STATE_PREFLIGHT ) {
2012-08-16 10:49:56 -03:00
mavlink_log_info ( mavlink_fd , " [commander] CMD starting mag calibration " ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-06 18:43:09 -03:00
do_mag_calibration ( status_pub , & current_status ) ;
2012-08-16 10:49:56 -03:00
mavlink_log_info ( mavlink_fd , " [commander] CMD finished mag calibration " ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-13 13:53:37 -03:00
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_STANDBY ) ;
2012-08-06 18:43:09 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
2012-08-16 10:49:56 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] CMD REJECTING mag calibration " ) ;
2012-08-06 18:43:09 -03:00
result = MAV_RESULT_DENIED ;
}
handled = true ;
2012-08-05 17:51:31 -03:00
}
2012-08-29 09:20:55 -03:00
/* accel calibration */
if ( ( int ) ( cmd - > param5 ) = = 1 ) {
/* transition to calibration state */
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_PREFLIGHT ) ;
if ( current_status . state_machine = = SYSTEM_STATE_PREFLIGHT ) {
mavlink_log_info ( mavlink_fd , " [commander] CMD starting accel calibration " ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-29 09:20:55 -03:00
do_accel_calibration ( status_pub , & current_status ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-29 09:20:55 -03:00
mavlink_log_info ( mavlink_fd , " [commander] CMD finished accel calibration " ) ;
do_state_update ( status_pub , & current_status , mavlink_fd , SYSTEM_STATE_STANDBY ) ;
result = MAV_RESULT_ACCEPTED ;
} else {
mavlink_log_critical ( mavlink_fd , " [commander] REJECTING accel calibration " ) ;
result = MAV_RESULT_DENIED ;
}
handled = true ;
}
2012-08-05 17:51:31 -03:00
/* none found */
if ( ! handled ) {
2012-08-16 10:49:56 -03:00
//fprintf(stderr, "[commander] refusing unsupported calibration request\n");
2012-09-27 11:50:20 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] CMD refusing unsup. calib. request " ) ;
2012-08-04 19:12:36 -03:00
result = MAV_RESULT_UNSUPPORTED ;
}
}
break ;
2012-08-20 18:52:13 -03:00
/*
* do not report an error for commands that are
* handled directly by MAVLink .
*/
case MAV_CMD_PREFLIGHT_STORAGE :
break ;
2012-08-13 13:53:37 -03:00
default : {
2012-08-04 19:12:36 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] refusing unsupported command " ) ;
result = MAV_RESULT_UNSUPPORTED ;
2012-10-22 08:28:53 -03:00
usleep ( 200000 ) ;
/* announce command rejection */
ioctl ( buzzer , TONE_SET_ALARM , 4 ) ;
2012-08-04 19:12:36 -03:00
}
break ;
}
/* supported command handling stop */
/* send any requested ACKs */
if ( cmd - > confirmation > 0 ) {
/* send acknowledge command */
2012-08-23 19:01:23 -03:00
// XXX TODO
2012-08-04 19:12:36 -03:00
}
}
2012-08-23 19:01:23 -03:00
static void * orb_receive_loop ( void * arg ) //handles status information coming from subsystems (present, enabled, health), these values do not indicate the quality (variance) of the signal
{
/* Set thread name */
prctl ( PR_SET_NAME , " commander orb rcv " , getpid ( ) ) ;
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
/* Subscribe to command topic */
int subsys_sub = orb_subscribe ( ORB_ID ( subsystem_info ) ) ;
struct subsystem_info_s info ;
2012-08-04 19:12:36 -03:00
2012-10-23 08:15:36 -03:00
struct vehicle_status_s * vstatus = ( struct vehicle_status_s * ) arg ;
2012-08-23 19:01:23 -03:00
while ( ! thread_should_exit ) {
struct pollfd fds [ 1 ] = { { . fd = subsys_sub , . events = POLLIN } } ;
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
if ( poll ( fds , 1 , 5000 ) = = 0 ) {
/* timeout, but this is no problem, silently ignore */
} else {
/* got command */
orb_copy ( ORB_ID ( subsystem_info ) , subsys_sub , & info ) ;
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
printf ( " Subsys changed: %d \n " , ( int ) info . subsystem_type ) ;
2012-10-23 08:15:36 -03:00
/* mark / unmark as present */
if ( info . present ) {
vstatus - > onboard_control_sensors_present | = info . subsystem_type ;
} else {
vstatus - > onboard_control_sensors_present & = ~ info . subsystem_type ;
}
/* mark / unmark as enabled */
if ( info . enabled ) {
vstatus - > onboard_control_sensors_enabled | = info . subsystem_type ;
} else {
vstatus - > onboard_control_sensors_enabled & = ~ info . subsystem_type ;
}
/* mark / unmark as ok */
if ( info . ok ) {
vstatus - > onboard_control_sensors_health | = info . subsystem_type ;
} else {
vstatus - > onboard_control_sensors_health & = ~ info . subsystem_type ;
}
2012-08-23 19:01:23 -03:00
}
}
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
close ( subsys_sub ) ;
2012-08-04 19:12:36 -03:00
2012-08-23 19:01:23 -03:00
return NULL ;
}
2012-08-04 19:12:36 -03:00
/*
* Provides a coarse estimate of remaining battery power .
*
* The estimate is very basic and based on decharging voltage curves .
*
* @ return the estimated remaining capacity in 0. .1
*/
2012-10-23 05:58:47 -03:00
float battery_remaining_estimate_voltage ( float voltage ) ;
2012-08-13 13:53:37 -03:00
2012-08-23 19:01:23 -03:00
PARAM_DEFINE_FLOAT ( BAT_V_EMPTY , 3.2f ) ;
PARAM_DEFINE_FLOAT ( BAT_V_FULL , 4.05f ) ;
2012-10-23 05:58:47 -03:00
PARAM_DEFINE_FLOAT ( BAT_N_CELLS , 3 ) ;
2012-08-20 18:52:13 -03:00
2012-10-23 05:58:47 -03:00
float battery_remaining_estimate_voltage ( float voltage )
2012-08-04 19:12:36 -03:00
{
float ret = 0 ;
2012-08-23 19:01:23 -03:00
static param_t bat_volt_empty ;
static param_t bat_volt_full ;
2012-10-23 05:58:47 -03:00
static param_t bat_n_cells ;
2012-08-23 19:01:23 -03:00
static bool initialized = false ;
static unsigned int counter = 0 ;
2012-10-23 05:58:47 -03:00
static float ncells = 3 ;
// XXX change cells to int (and param to INT32)
2012-08-23 19:01:23 -03:00
if ( ! initialized ) {
bat_volt_empty = param_find ( " BAT_V_EMPTY " ) ;
bat_volt_full = param_find ( " BAT_V_FULL " ) ;
2012-10-23 05:58:47 -03:00
bat_n_cells = param_find ( " BAT_N_CELLS " ) ;
2012-08-23 19:01:23 -03:00
initialized = true ;
}
2012-10-23 05:58:47 -03:00
static float chemistry_voltage_empty = 3.2f ;
static float chemistry_voltage_full = 4.05f ;
2012-08-23 19:01:23 -03:00
if ( counter % 100 = = 0 ) {
2012-10-23 05:58:47 -03:00
param_get ( bat_volt_empty , & chemistry_voltage_empty ) ;
param_get ( bat_volt_full , & chemistry_voltage_full ) ;
param_get ( bat_n_cells , & ncells ) ;
2012-08-23 19:01:23 -03:00
}
counter + + ;
2012-08-04 19:12:36 -03:00
2012-10-23 05:58:47 -03:00
ret = ( voltage - ncells * chemistry_voltage_empty ) / ( ncells * ( chemistry_voltage_full - chemistry_voltage_empty ) ) ;
2012-08-04 19:12:36 -03:00
/* limit to sane values */
ret = ( ret < 0 ) ? 0 : ret ;
ret = ( ret > 1 ) ? 1 : ret ;
return ret ;
}
2012-08-20 18:52:13 -03:00
static void
usage ( const char * reason )
{
if ( reason )
fprintf ( stderr , " %s \n " , reason ) ;
2012-10-23 08:15:36 -03:00
fprintf ( stderr , " usage: daemon {start|stop|status} [-p <additional params>] \n \n " ) ;
2012-08-20 18:52:13 -03:00
exit ( 1 ) ;
}
2012-08-04 19:12:36 -03:00
2012-08-20 18:52:13 -03:00
/**
2012-10-23 08:15:36 -03:00
* The daemon app only briefly exists to start
2012-08-20 18:52:13 -03:00
* 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 ( ) .
*/
2012-08-04 19:12:36 -03:00
int commander_main ( int argc , char * argv [ ] )
2012-08-20 18:52:13 -03:00
{
if ( argc < 1 )
usage ( " missing command " ) ;
if ( ! strcmp ( argv [ 1 ] , " start " ) ) {
if ( thread_running ) {
printf ( " commander already running \n " ) ;
/* this is not an error */
exit ( 0 ) ;
}
thread_should_exit = false ;
2012-10-23 08:15:36 -03:00
daemon_task = task_spawn ( " commander " ,
2012-10-04 03:13:20 -03:00
SCHED_DEFAULT ,
2012-10-01 04:02:38 -03:00
SCHED_PRIORITY_MAX - 50 ,
2012-10-10 12:47:28 -03:00
8000 ,
2012-10-01 04:02:38 -03:00
commander_thread_main ,
( argv ) ? ( const char * * ) & argv [ 2 ] : ( const char * * ) NULL ) ;
2012-08-20 18:52:13 -03:00
thread_running = true ;
exit ( 0 ) ;
}
if ( ! strcmp ( argv [ 1 ] , " stop " ) ) {
thread_should_exit = true ;
exit ( 0 ) ;
}
if ( ! strcmp ( argv [ 1 ] , " status " ) ) {
if ( thread_running ) {
printf ( " \t commander is running \n " ) ;
} else {
printf ( " \t commander not started \n " ) ;
}
exit ( 0 ) ;
}
usage ( " unrecognized command " ) ;
exit ( 1 ) ;
}
int commander_thread_main ( int argc , char * argv [ ] )
2012-08-04 19:12:36 -03:00
{
/* not yet initialized */
commander_initialized = false ;
2012-09-21 07:55:41 -03:00
/* set parameters */
failsafe_lowlevel_timeout_ms = 0 ;
param_get ( param_find ( " SYS_FAILSAVE_LL " ) , & failsafe_lowlevel_timeout_ms ) ;
2012-08-04 19:12:36 -03:00
/* welcome user */
printf ( " [commander] I am in command now! \n " ) ;
2012-08-23 19:01:23 -03:00
/* pthreads for command and subsystem info handling */
2012-10-15 03:52:41 -03:00
// pthread_t command_handling_thread;
2012-08-23 19:01:23 -03:00
pthread_t subsystem_info_thread ;
2012-08-04 19:12:36 -03:00
/* initialize */
if ( led_init ( ) ! = 0 ) {
fprintf ( stderr , " [commander] ERROR: Failed to initialize leds \n " ) ;
}
if ( buzzer_init ( ) ! = 0 ) {
fprintf ( stderr , " [commander] ERROR: Failed to initialize buzzer \n " ) ;
}
mavlink_fd = open ( MAVLINK_LOG_DEVICE , 0 ) ;
if ( mavlink_fd < 0 ) {
fprintf ( stderr , " [commander] ERROR: Failed to open MAVLink log stream, start mavlink app first. \n " ) ;
}
2012-08-13 13:53:37 -03:00
/* make sure we are in preflight state */
memset ( & current_status , 0 , sizeof ( current_status ) ) ;
current_status . state_machine = SYSTEM_STATE_PREFLIGHT ;
2012-08-18 11:48:43 -03:00
current_status . flag_system_armed = false ;
2012-10-02 08:02:57 -03:00
/* neither manual nor offboard control commands have been received */
2012-09-26 16:30:03 -03:00
current_status . offboard_control_signal_found_once = false ;
current_status . rc_signal_found_once = false ;
2012-10-02 08:02:57 -03:00
/* mark all signals lost as long as they haven't been found */
current_status . rc_signal_lost = true ;
current_status . offboard_control_signal_lost = true ;
2012-08-13 13:53:37 -03:00
2012-08-04 19:12:36 -03:00
/* advertise to ORB */
stat_pub = orb_advertise ( ORB_ID ( vehicle_status ) , & current_status ) ;
2012-08-16 10:49:56 -03:00
/* publish current state machine */
2012-08-13 13:53:37 -03:00
state_machine_publish ( stat_pub , & current_status , mavlink_fd ) ;
2012-08-04 19:12:36 -03:00
if ( stat_pub < 0 ) {
2012-08-11 14:45:32 -03:00
printf ( " [commander] ERROR: orb_advertise for topic vehicle_status failed. \n " ) ;
exit ( ERROR ) ;
2012-08-04 19:12:36 -03:00
}
mavlink_log_info ( mavlink_fd , " [commander] system is running " ) ;
/* create pthreads */
2012-08-23 19:01:23 -03:00
pthread_attr_t subsystem_info_attr ;
pthread_attr_init ( & subsystem_info_attr ) ;
pthread_attr_setstacksize ( & subsystem_info_attr , 2048 ) ;
2012-10-23 08:15:36 -03:00
pthread_create ( & subsystem_info_thread , & subsystem_info_attr , orb_receive_loop , & current_status ) ;
2012-08-04 19:12:36 -03:00
/* Start monitoring loop */
uint16_t counter = 0 ;
uint8_t flight_env ;
2012-08-23 19:01:23 -03:00
2012-08-04 19:12:36 -03:00
/* Initialize to 3.0V to make sure the low-pass loads below valid threshold */
2012-09-05 13:05:11 -03:00
float battery_voltage = 12.0f ;
2012-08-04 19:12:36 -03:00
bool battery_voltage_valid = true ;
bool low_battery_voltage_actions_done = false ;
bool critical_battery_voltage_actions_done = false ;
uint8_t low_voltage_counter = 0 ;
uint16_t critical_voltage_counter = 0 ;
int16_t mode_switch_rc_value ;
float bat_remain = 1.0f ;
uint16_t stick_off_counter = 0 ;
uint16_t stick_on_counter = 0 ;
float hdop = 65535.0f ;
int gps_quality_good_counter = 0 ;
2012-09-21 07:55:41 -03:00
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe ( ORB_ID ( manual_control_setpoint ) ) ;
struct manual_control_setpoint_s sp_man ;
memset ( & sp_man , 0 , sizeof ( sp_man ) ) ;
/* Subscribe to offboard control data */
int sp_offboard_sub = orb_subscribe ( ORB_ID ( offboard_control_setpoint ) ) ;
struct offboard_control_setpoint_s sp_offboard ;
memset ( & sp_offboard , 0 , sizeof ( sp_offboard ) ) ;
2012-08-04 19:12:36 -03:00
int gps_sub = orb_subscribe ( ORB_ID ( vehicle_gps_position ) ) ;
2012-08-05 17:51:31 -03:00
struct vehicle_gps_position_s gps ;
memset ( & gps , 0 , sizeof ( gps ) ) ;
2012-08-04 19:12:36 -03:00
int sensor_sub = orb_subscribe ( ORB_ID ( sensor_combined ) ) ;
2012-08-05 17:51:31 -03:00
struct sensor_combined_s sensors ;
memset ( & sensors , 0 , sizeof ( sensors ) ) ;
2012-08-04 19:12:36 -03:00
2012-10-15 03:52:41 -03: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-08-13 13:53:37 -03:00
// uint8_t vehicle_state_previous = current_status.state_machine;
2012-08-08 13:47:46 -03:00
float voltage_previous = 0.0f ;
2012-08-04 19:12:36 -03:00
uint64_t last_idle_time = 0 ;
/* now initialized */
commander_initialized = true ;
2012-09-05 13:05:11 -03:00
uint64_t start_time = hrt_absolute_time ( ) ;
2012-09-21 07:55:41 -03:00
uint64_t failsave_ll_start_time = 0 ;
bool state_changed = true ;
2012-09-05 13:05:11 -03:00
2012-08-23 19:01:23 -03:00
while ( ! thread_should_exit ) {
2012-08-04 19:12:36 -03:00
/* Get current values */
2012-09-26 16:30:03 -03:00
bool new_data ;
orb_check ( sp_man_sub , & new_data ) ;
if ( new_data ) {
orb_copy ( ORB_ID ( manual_control_setpoint ) , sp_man_sub , & sp_man ) ;
}
orb_check ( sp_offboard_sub , & new_data ) ;
if ( new_data ) {
orb_copy ( ORB_ID ( offboard_control_setpoint ) , sp_offboard_sub , & sp_offboard ) ;
}
2012-08-04 19:12:36 -03:00
orb_copy ( ORB_ID ( vehicle_gps_position ) , gps_sub , & gps ) ;
orb_copy ( ORB_ID ( sensor_combined ) , sensor_sub , & sensors ) ;
2012-10-15 03:52:41 -03:00
orb_check ( cmd_sub , & new_data ) ;
if ( new_data ) {
/* got command */
orb_copy ( ORB_ID ( vehicle_command ) , cmd_sub , & cmd ) ;
/* handle it */
handle_command ( stat_pub , & current_status , & cmd ) ;
}
2012-08-04 19:12:36 -03:00
battery_voltage = sensors . battery_voltage_v ;
battery_voltage_valid = sensors . battery_voltage_valid ;
2012-09-05 13:05:11 -03:00
/*
* Only update battery voltage estimate if voltage is
2012-09-07 07:40:40 -03:00
* valid and system has been running for two and a half seconds
2012-09-05 13:05:11 -03:00
*/
2012-09-07 07:40:40 -03:00
if ( battery_voltage_valid & & ( hrt_absolute_time ( ) - start_time > 2500000 ) ) {
2012-10-23 05:58:47 -03:00
bat_remain = battery_remaining_estimate_voltage ( battery_voltage ) ;
2012-09-05 13:05:11 -03:00
}
2012-08-04 19:12:36 -03:00
2012-08-16 10:49:56 -03:00
/* Slow but important 8 Hz checks */
2012-08-04 19:12:36 -03:00
if ( counter % ( ( 1000000 / COMMANDER_MONITORING_INTERVAL ) / 8 ) = = 0 ) {
/* toggle activity (blue) led at 1 Hz in standby, 10 Hz in armed mode */
2012-08-08 13:47:46 -03:00
if ( ( current_status . state_machine = = SYSTEM_STATE_GROUND_READY | |
current_status . state_machine = = SYSTEM_STATE_AUTO | |
current_status . state_machine = = SYSTEM_STATE_MANUAL ) ) {
2012-08-04 19:12:36 -03:00
/* armed */
led_toggle ( LED_BLUE ) ;
} else if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
/* not armed */
led_toggle ( LED_BLUE ) ;
}
/* toggle error led at 5 Hz in HIL mode */
2012-08-18 11:48:43 -03:00
if ( current_status . flag_hil_enabled ) {
/* hil enabled */
2012-08-04 19:12:36 -03:00
led_toggle ( LED_AMBER ) ;
} else if ( bat_remain < 0.3f & & ( low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT ) ) {
/* toggle error (red) at 5 Hz on low battery or error */
led_toggle ( LED_AMBER ) ;
} else {
2012-08-27 17:57:20 -03:00
// /* Constant error indication in standby mode without GPS */
// if (!current_status.gps_valid) {
// led_on(LED_AMBER);
2012-08-04 19:12:36 -03:00
2012-08-27 17:57:20 -03:00
// } else {
// led_off(LED_AMBER);
// }
2012-08-04 19:12:36 -03:00
}
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 ) {
2012-08-08 13:47:46 -03:00
/* compute system load */
2012-08-04 19:12:36 -03:00
uint64_t interval_runtime = system_load . tasks [ 0 ] . total_runtime - last_idle_time ;
if ( last_idle_time > 0 )
current_status . load = 1000 - ( interval_runtime / 1000 ) ; //system load is time spent in non-idle
last_idle_time = system_load . tasks [ 0 ] . total_runtime ;
}
}
// // XXX Export patterns and threshold to parameters
/* Trigger audio event for low battery */
if ( bat_remain < 0.1f & & battery_voltage_valid & & ( counter % ( ( 1000000 / COMMANDER_MONITORING_INTERVAL ) / 4 ) = = 0 ) ) {
/* For less than 10%, start be really annoying at 5 Hz */
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
ioctl ( buzzer , TONE_SET_ALARM , 3 ) ;
} else if ( bat_remain < 0.1f & & battery_voltage_valid & & ( counter % ( ( 1000000 / COMMANDER_MONITORING_INTERVAL ) / 4 ) = = 2 ) ) {
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
} else if ( bat_remain < 0.2f & & battery_voltage_valid & & ( counter % ( ( 1000000 / COMMANDER_MONITORING_INTERVAL ) / 2 ) = = 0 ) ) {
/* For less than 20%, start be slightly annoying at 1 Hz */
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
2012-10-22 08:58:13 -03:00
tune_confirm ( ) ;
2012-08-04 19:12:36 -03:00
} else if ( bat_remain < 0.2f & & battery_voltage_valid & & ( counter % ( ( 1000000 / COMMANDER_MONITORING_INTERVAL ) / 2 ) = = 2 ) ) {
ioctl ( buzzer , TONE_SET_ALARM , 0 ) ;
}
2012-09-05 13:05:11 -03:00
/* Check battery voltage */
/* write to sys_status */
current_status . voltage_battery = battery_voltage ;
/* if battery voltage is getting lower, warn using buzzer, etc. */
if ( battery_voltage_valid & & ( bat_remain < 0.15f /* XXX MAGIC NUMBER */ ) & & ( false = = low_battery_voltage_actions_done ) ) { //TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
if ( low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT ) {
low_battery_voltage_actions_done = true ;
mavlink_log_critical ( mavlink_fd , " [commander] WARNING! LOW BATTERY! " ) ;
}
low_voltage_counter + + ;
}
/* Critical, this is rather an emergency, kill signal to sdlog and change state machine */
else if ( battery_voltage_valid & & ( bat_remain < 0.1f /* XXX MAGIC NUMBER */ ) & & ( false = = critical_battery_voltage_actions_done & & true = = low_battery_voltage_actions_done ) ) {
if ( critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT ) {
critical_battery_voltage_actions_done = true ;
mavlink_log_critical ( mavlink_fd , " [commander] EMERGENCY! CIRITICAL BATTERY! " ) ;
state_machine_emergency ( stat_pub , & current_status , mavlink_fd ) ;
}
critical_voltage_counter + + ;
} else {
low_voltage_counter = 0 ;
critical_voltage_counter = 0 ;
}
/* End battery voltage check */
2012-08-04 19:12:36 -03:00
/* Check if last transition deserved an audio event */
2012-09-21 07:55:41 -03:00
// #warning This code depends on state that is no longer? maintained
// #if 0
// trigger_audio_alarm(vehicle_mode_previous, vehicle_state_previous, current_status.mode, current_status.state_machine);
// #endif
2012-08-04 19:12:36 -03:00
/* only check gps fix if we are outdoor */
// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
//
// hdop = (float)(gps.eph) / 100.0f;
//
// /* check if gps fix is ok */
// if (gps.fix_type == GPS_FIX_TYPE_3D) { //TODO: is 2d-fix ok? //see http://en.wikipedia.org/wiki/Dilution_of_precision_%28GPS%29
//
// if (gotfix_counter >= GPS_GOTFIX_COUNTER_REQUIRED) { //TODO: add also a required time?
// update_state_machine_got_position_fix(stat_pub, ¤t_status);
// gotfix_counter = 0;
// } else {
// gotfix_counter++;
// }
// nofix_counter = 0;
//
// if (hdop < 5.0f) { //TODO: this should be a parameter
// if (gps_quality_good_counter > GPS_QUALITY_GOOD_COUNTER_LIMIT) {
// current_status.gps_valid = true;//--> position estimator can use the gps measurements
// }
//
// gps_quality_good_counter++;
//
//
//// if(counter%10 == 0)//for testing only
//// printf("gps_quality_good_counter = %u\n", gps_quality_good_counter);//for testing only
//
// } else {
// gps_quality_good_counter = 0;
// current_status.gps_valid = false;//--> position estimator can not use the gps measurements
// }
//
// } else {
// gps_quality_good_counter = 0;
// current_status.gps_valid = false;//--> position estimator can not use the gps measurements
//
// if (nofix_counter > GPS_NOFIX_COUNTER_LIMIT) { //TODO: add also a timer limit?
// update_state_machine_no_position_fix(stat_pub, ¤t_status);
// nofix_counter = 0;
// } else {
// nofix_counter++;
// }
// gotfix_counter = 0;
// }
//
// }
//
//
// if (flight_env == PX4_FLIGHT_ENVIRONMENT_TESTING) //simulate position fix for quick indoor tests
2012-08-16 10:49:56 -03:00
//update_state_machine_got_position_fix(stat_pub, ¤t_status, mavlink_fd);
2012-08-04 19:12:36 -03:00
/* end: check gps */
2012-09-21 07:55:41 -03:00
/* ignore RC signals if in offboard control mode */
2012-09-26 16:30:03 -03:00
if ( ! current_status . offboard_control_signal_found_once & & sp_man . timestamp ! = 0 ) {
2012-09-21 07:55:41 -03:00
/* Start RC state check */
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
if ( ( hrt_absolute_time ( ) - sp_man . timestamp ) < 100000 ) {
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
/* check if left stick is in lower left position --> switch to standby state */
if ( ( sp_man . yaw < - STICK_ON_OFF_LIMIT ) & & sp_man . throttle < STICK_THRUST_RANGE * 0.2f ) { //TODO: remove hardcoded values
if ( stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT ) {
update_state_machine_disarm ( stat_pub , & current_status , mavlink_fd ) ;
stick_on_counter = 0 ;
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
} else {
stick_off_counter + + ;
stick_on_counter = 0 ;
}
}
2012-08-08 13:47:46 -03:00
2012-09-21 07:55:41 -03:00
/* check if left stick is in lower right position --> arm */
if ( sp_man . yaw > STICK_ON_OFF_LIMIT & & sp_man . throttle < STICK_THRUST_RANGE * 0.2f ) { //TODO: remove hardcoded values
if ( stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT ) {
update_state_machine_arm ( stat_pub , & current_status , mavlink_fd ) ;
stick_on_counter = 0 ;
2012-08-08 13:47:46 -03:00
2012-09-21 07:55:41 -03:00
} else {
stick_on_counter + + ;
stick_off_counter = 0 ;
}
2012-08-08 13:47:46 -03:00
}
2012-09-21 07:55:41 -03:00
//printf("RC: y:%i/t:%i s:%i chans: %i\n", rc_yaw_scale, rc_throttle_scale, mode_switch_rc_value, rc.chan_count);
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
if ( sp_man . override_mode_switch > STICK_ON_OFF_LIMIT ) {
update_state_machine_mode_manual ( stat_pub , & current_status , mavlink_fd ) ;
} else if ( sp_man . override_mode_switch < - STICK_ON_OFF_LIMIT ) {
update_state_machine_mode_auto ( stat_pub , & current_status , mavlink_fd ) ;
2012-08-04 19:12:36 -03:00
2012-08-08 13:47:46 -03:00
} else {
2012-09-21 07:55:41 -03:00
update_state_machine_mode_stabilized ( stat_pub , & current_status , mavlink_fd ) ;
2012-08-08 13:47:46 -03:00
}
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
/* handle the case where RC signal was regained */
if ( ! current_status . rc_signal_found_once ) {
current_status . rc_signal_found_once = true ;
mavlink_log_critical ( mavlink_fd , " [commander] DETECTED RC SIGNAL FIRST TIME. " ) ;
} else {
if ( current_status . rc_signal_lost ) mavlink_log_critical ( mavlink_fd , " [commander] RECOVERY - RC SIGNAL GAINED! " ) ;
}
2012-08-04 19:12:36 -03:00
2012-09-26 16:30:03 -03:00
current_status . rc_signal_cutting_off = false ;
2012-09-21 07:55:41 -03:00
current_status . rc_signal_lost = false ;
current_status . rc_signal_lost_interval = 0 ;
2012-08-08 13:47:46 -03:00
} else {
2012-09-21 07:55:41 -03:00
static uint64_t last_print_time = 0 ;
/* print error message for first RC glitch and then every 5 s / 5000 ms) */
2012-09-26 16:30:03 -03:00
if ( ! current_status . rc_signal_cutting_off | | ( ( hrt_absolute_time ( ) - last_print_time ) > 5000000 ) ) {
2012-09-21 07:55:41 -03:00
/* only complain if the offboard control is NOT active */
2012-09-26 16:30:03 -03:00
current_status . rc_signal_cutting_off = true ;
2012-09-21 07:55:41 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] CRITICAL - NO REMOTE SIGNAL! " ) ;
last_print_time = hrt_absolute_time ( ) ;
}
/* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
current_status . rc_signal_lost_interval = hrt_absolute_time ( ) - sp_man . timestamp ;
/* if the RC signal is gone for a full second, consider it lost */
if ( current_status . rc_signal_lost_interval > 1000000 ) {
current_status . rc_signal_lost = true ;
current_status . failsave_lowlevel = true ;
2012-09-26 16:30:03 -03:00
state_changed = true ;
2012-09-21 07:55:41 -03:00
}
2012-08-04 19:12:36 -03:00
2012-09-21 07:55:41 -03:00
// if (hrt_absolute_time() - current_status.failsave_ll_start_time > failsafe_lowlevel_timeout_ms*1000) {
// publish_armed_status(¤t_status);
// }
2012-08-08 13:47:46 -03:00
}
2012-08-04 19:12:36 -03:00
}
2012-09-21 07:55:41 -03:00
2012-09-05 06:37:17 -03:00
2012-08-04 19:12:36 -03:00
/* End mode switch */
/* END RC state check */
2012-09-21 07:55:41 -03:00
/* State machine update for offboard control */
2012-09-26 16:30:03 -03:00
if ( ! current_status . rc_signal_found_once & & sp_offboard . timestamp ! = 0 ) {
2012-09-21 07:55:41 -03:00
if ( ( hrt_absolute_time ( ) - sp_offboard . timestamp ) < 5000000 ) {
2012-09-26 16:30:03 -03:00
/* decide about attitude control flag, enable in att/pos/vel */
bool attitude_ctrl_enabled = ( sp_offboard . mode = = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE | |
sp_offboard . mode = = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY | |
sp_offboard . mode = = OFFBOARD_CONTROL_MODE_DIRECT_POSITION ) ;
/* decide about rate control flag, enable it always XXX (for now) */
bool rates_ctrl_enabled = true ;
2012-09-21 07:55:41 -03:00
/* set up control mode */
2012-09-26 16:30:03 -03:00
if ( current_status . flag_control_attitude_enabled ! = attitude_ctrl_enabled ) {
current_status . flag_control_attitude_enabled = attitude_ctrl_enabled ;
2012-09-21 07:55:41 -03:00
state_changed = true ;
}
2012-09-26 16:30:03 -03:00
if ( current_status . flag_control_rates_enabled ! = rates_ctrl_enabled ) {
current_status . flag_control_rates_enabled = rates_ctrl_enabled ;
2012-09-21 07:55:41 -03:00
state_changed = true ;
}
2012-09-26 16:30:03 -03:00
/* handle the case where offboard control signal was regained */
2012-09-21 07:55:41 -03:00
if ( ! current_status . offboard_control_signal_found_once ) {
current_status . offboard_control_signal_found_once = true ;
/* enable offboard control, disable manual input */
current_status . flag_control_manual_enabled = false ;
current_status . flag_control_offboard_enabled = true ;
state_changed = true ;
mavlink_log_critical ( mavlink_fd , " [commander] DETECTED OFFBOARD CONTROL SIGNAL FIRST TIME. " ) ;
} else {
if ( current_status . offboard_control_signal_lost ) {
mavlink_log_critical ( mavlink_fd , " [commander] RECOVERY - OFFBOARD CONTROL SIGNAL GAINED! " ) ;
state_changed = true ;
}
}
2012-09-26 16:30:03 -03:00
current_status . offboard_control_signal_weak = false ;
2012-09-21 07:55:41 -03:00
current_status . offboard_control_signal_lost = false ;
current_status . offboard_control_signal_lost_interval = 0 ;
/* arm / disarm on request */
if ( sp_offboard . armed & & ! current_status . flag_system_armed ) {
update_state_machine_arm ( stat_pub , & current_status , mavlink_fd ) ;
/* switch to stabilized mode = takeoff */
update_state_machine_mode_stabilized ( stat_pub , & current_status , mavlink_fd ) ;
} else if ( ! sp_offboard . armed & & current_status . flag_system_armed ) {
update_state_machine_disarm ( stat_pub , & current_status , mavlink_fd ) ;
}
} else {
static uint64_t last_print_time = 0 ;
/* print error message for first RC glitch and then every 5 s / 5000 ms) */
2012-09-26 16:30:03 -03:00
if ( ! current_status . offboard_control_signal_weak | | ( ( hrt_absolute_time ( ) - last_print_time ) > 5000000 ) ) {
current_status . offboard_control_signal_weak = true ;
2012-09-21 07:55:41 -03:00
mavlink_log_critical ( mavlink_fd , " [commander] CRITICAL - NO OFFBOARD CONTROL SIGNAL! " ) ;
last_print_time = hrt_absolute_time ( ) ;
}
/* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
current_status . offboard_control_signal_lost_interval = hrt_absolute_time ( ) - sp_offboard . timestamp ;
/* if the signal is gone for 0.1 seconds, consider it lost */
if ( current_status . offboard_control_signal_lost_interval > 100000 ) {
current_status . offboard_control_signal_lost = true ;
current_status . failsave_lowlevel_start_time = hrt_absolute_time ( ) ;
current_status . failsave_lowlevel = true ;
/* kill motors after timeout */
if ( hrt_absolute_time ( ) - current_status . failsave_lowlevel_start_time > failsafe_lowlevel_timeout_ms * 1000 ) {
state_changed = true ;
}
}
}
}
2012-08-04 19:12:36 -03:00
current_status . counter + + ;
current_status . timestamp = hrt_absolute_time ( ) ;
2012-08-16 10:49:56 -03:00
2012-08-08 13:47:46 -03:00
/* If full run came back clean, transition to standby */
if ( current_status . state_machine = = SYSTEM_STATE_PREFLIGHT & &
2012-08-29 09:20:55 -03:00
current_status . flag_preflight_gyro_calibration = = false & &
current_status . flag_preflight_mag_calibration = = false & &
current_status . flag_preflight_accel_calibration = = false ) {
2012-08-08 13:47:46 -03:00
/* All ok, no calibration going on, go to standby */
2012-08-16 12:20:41 -03:00
do_state_update ( stat_pub , & current_status , mavlink_fd , SYSTEM_STATE_STANDBY ) ;
2012-08-08 13:47:46 -03:00
}
2012-08-04 19:12:36 -03:00
2012-08-16 10:49:56 -03:00
/* publish at least with 1 Hz */
2012-09-21 07:55:41 -03:00
if ( counter % ( 1000000 / COMMANDER_MONITORING_INTERVAL ) = = 0 | | state_changed ) {
publish_armed_status ( & current_status ) ;
2012-08-16 10:49:56 -03:00
orb_publish ( ORB_ID ( vehicle_status ) , stat_pub , & current_status ) ;
2012-09-21 07:55:41 -03:00
state_changed = false ;
2012-08-16 10:49:56 -03:00
}
2012-08-04 19:12:36 -03:00
/* Store old modes to detect and act on state transitions */
2012-08-08 13:47:46 -03:00
voltage_previous = current_status . voltage_battery ;
2012-08-04 19:12:36 -03:00
fflush ( stdout ) ;
counter + + ;
usleep ( COMMANDER_MONITORING_INTERVAL ) ;
}
/* wait for threads to complete */
2012-10-15 03:52:41 -03:00
// pthread_join(command_handling_thread, NULL);
2012-08-23 19:01:23 -03:00
pthread_join ( subsystem_info_thread , NULL ) ;
2012-08-04 19:12:36 -03:00
/* close fds */
led_deinit ( ) ;
buzzer_deinit ( ) ;
2012-09-21 07:55:41 -03:00
close ( sp_man_sub ) ;
close ( sp_offboard_sub ) ;
2012-08-23 19:01:23 -03:00
close ( gps_sub ) ;
close ( sensor_sub ) ;
2012-10-15 03:52:41 -03:00
close ( cmd_sub ) ;
2012-08-23 19:01:23 -03:00
printf ( " [commander] exiting.. \n " ) ;
fflush ( stdout ) ;
2012-08-04 19:12:36 -03:00
2012-08-20 18:52:13 -03:00
thread_running = false ;
2012-08-04 19:12:36 -03:00
return 0 ;
}