From d1261e227cd687d948609bb522d19e404cdd9c13 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 20 Aug 2012 23:52:13 +0200 Subject: Porting to new param interface, updated mixers --- apps/commander/Makefile | 2 +- apps/commander/commander.c | 108 ++++++++++++++++++++++---- apps/examples/px4_deamon_app/px4_deamon_app.c | 6 +- apps/mavlink/Makefile | 2 +- apps/mavlink/mavlink.c | 2 +- apps/sensors/sensors.c | 60 +++++++++++++- 6 files changed, 158 insertions(+), 22 deletions(-) (limited to 'apps') diff --git a/apps/commander/Makefile b/apps/commander/Makefile index f2972ac4e..d12697274 100644 --- a/apps/commander/Makefile +++ b/apps/commander/Makefile @@ -37,7 +37,7 @@ APPNAME = commander PRIORITY = SCHED_PRIORITY_MAX - 30 -STACKSIZE = 4096 +STACKSIZE = 2048 INCLUDES = $(TOPDIR)/../mavlink/include/mavlink diff --git a/apps/commander/commander.c b/apps/commander/commander.c index a81e102e9..424bef140 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -69,7 +69,8 @@ #include #include #include - + +#include #include #include @@ -95,15 +96,15 @@ static int leds; static int buzzer; static int mavlink_fd; static bool commander_initialized = false; -static struct vehicle_status_s current_status; /**< Main state machine */ +static struct vehicle_status_s current_status; /**< Main state machine */ static int stat_pub; static uint16_t nofix_counter = 0; static uint16_t gotfix_counter = 0; -static void do_gyro_calibration(int status_pub, struct vehicle_status_s *current_status); -static void do_mag_calibration(int status_pub, struct vehicle_status_s *current_status); -static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd); +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ /* pthread loops */ static void *command_handling_loop(void *arg); @@ -111,9 +112,30 @@ static void *command_handling_loop(void *arg); __EXPORT int commander_main(int argc, char *argv[]); -#ifdef CONFIG_TONE_ALARM +/** + * Mainloop of commander. + */ +int commander_thread_main(int argc, char *argv[]); + static int buzzer_init(void); static void buzzer_deinit(void); +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); +static void do_gyro_calibration(int status_pub, struct vehicle_status_s *current_status); +static void do_mag_calibration(int status_pub, struct vehicle_status_s *current_status); +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); static int buzzer_init() { @@ -131,13 +153,7 @@ static void buzzer_deinit() { close(buzzer); } -#endif -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); static int led_init() { @@ -581,6 +597,13 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta } break; + /* + * do not report an error for commands that are + * handled directly by MAVLink. + */ + case MAV_CMD_PREFLIGHT_STORAGE: + break; + default: { mavlink_log_critical(mavlink_fd, "[commander] refusing unsupported command"); result = MAV_RESULT_UNSUPPORTED; @@ -705,6 +728,9 @@ enum BAT_CHEM { */ float battery_remaining_estimate_voltage(int cells, int chemistry, float voltage); +PARAM_DEFINE_FLOAT(BAT_VOLT_EMPTY, 3.2f); +PARAM_DEFINE_FLOAT(BAT_VOLT_FULL, 4.05f); + float battery_remaining_estimate_voltage(int cells, int chemistry, float voltage) { float ret = 0; @@ -721,11 +747,61 @@ float battery_remaining_estimate_voltage(int cells, int chemistry, float voltage return ret; } -/**************************************************************************** - * Name: commander - ****************************************************************************/ +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + fprintf(stderr, "usage: deamon {start|stop|status} [-p ]\n\n"); + exit(1); +} +/** + * The deamon 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(). + */ int commander_main(int argc, char *argv[]) +{ + 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; + deamon_task = task_create("commander", SCHED_PRIORITY_MAX - 50, 4096, commander_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); + 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("\tcommander is running\n"); + } else { + printf("\tcommander not started\n"); + } + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int commander_thread_main(int argc, char *argv[]) { /* not yet initialized */ commander_initialized = false; @@ -1108,6 +1184,8 @@ int commander_main(int argc, char *argv[]) led_deinit(); buzzer_deinit(); + thread_running = false; + return 0; } diff --git a/apps/examples/px4_deamon_app/px4_deamon_app.c b/apps/examples/px4_deamon_app/px4_deamon_app.c index 91e60a8f9..052a36cb9 100644 --- a/apps/examples/px4_deamon_app/px4_deamon_app.c +++ b/apps/examples/px4_deamon_app/px4_deamon_app.c @@ -42,8 +42,8 @@ #include static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ /** * Deamon management function. @@ -94,7 +94,7 @@ usage(const char *reason) */ int px4_deamon_app_main(int argc, char *argv[]) { - if (argc < 1) + if (argc < 1) usage("missing command"); if (!strcmp(argv[1], "start")) { diff --git a/apps/mavlink/Makefile b/apps/mavlink/Makefile index d4e9a5762..8ddb69b71 100644 --- a/apps/mavlink/Makefile +++ b/apps/mavlink/Makefile @@ -37,7 +37,7 @@ APPNAME = mavlink PRIORITY = SCHED_PRIORITY_DEFAULT -STACKSIZE = 4096 +STACKSIZE = 2048 INCLUDES = $(TOPDIR)/../mavlink/include/mavlink diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 653a41090..1bcbb2aa4 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -1447,7 +1447,7 @@ int mavlink_main(int argc, char *argv[]) } thread_should_exit = false; - mavlink_task = task_create("mavlink", SCHED_PRIORITY_DEFAULT, 4096, mavlink_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); + mavlink_task = task_create("mavlink", SCHED_PRIORITY_DEFAULT, 4400, mavlink_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); thread_running = true; exit(0); } diff --git a/apps/sensors/sensors.c b/apps/sensors/sensors.c index ef8ff798f..b802eff34 100644 --- a/apps/sensors/sensors.c +++ b/apps/sensors/sensors.c @@ -60,6 +60,8 @@ #include #include +#include + #include #include #include @@ -124,9 +126,65 @@ extern unsigned ppm_decoded_channels; extern uint64_t ppm_last_valid_decode; #endif -/* file handle that will be used for subscribing */ +/* file handle that will be used for publishing sensor data */ static int sensor_pub; +PARAM_DEFINE_FLOAT(sensor_gyro_xoffset, 0.0f); +PARAM_DEFINE_FLOAT(sensor_gyro_yoffset, 0.0f); +PARAM_DEFINE_FLOAT(sensor_gyro_zoffset, 0.0f); + +PARAM_DEFINE_FLOAT(sensor_mag_xoff, 0.0f); +PARAM_DEFINE_FLOAT(sensor_mag_yoff, 0.0f); +PARAM_DEFINE_FLOAT(sensor_mag_zoff, 0.0f); + +PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); +PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); +PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f); +PARAM_DEFINE_FLOAT(RC1_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC2_MIN, 1000); +PARAM_DEFINE_FLOAT(RC2_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC2_MAX, 2000); +PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC3_MIN, 1000); +PARAM_DEFINE_FLOAT(RC3_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC3_MAX, 2000); +PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC4_MIN, 1000); +PARAM_DEFINE_FLOAT(RC4_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC4_MAX, 2000); +PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC5_MIN, 1000); +PARAM_DEFINE_FLOAT(RC5_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC5_MAX, 2000); +PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC6_MIN, 1000); +PARAM_DEFINE_FLOAT(RC6_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC6_MAX, 2000); +PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC7_MIN, 1000); +PARAM_DEFINE_FLOAT(RC7_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC7_MAX, 2000); +PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); + +PARAM_DEFINE_FLOAT(RC8_MIN, 1000); +PARAM_DEFINE_FLOAT(RC8_TRIM, 1500); +PARAM_DEFINE_FLOAT(RC8_MAX, 2000); +PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); + +PARAM_DEFINE_INT32(RC_TYPE, 1); // 1 = FUTABA + +PARAM_DEFINE_INT32(RC_MAP_ROLL, 1); +PARAM_DEFINE_INT32(RC_MAP_PITCH, 2); +PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 3); +PARAM_DEFINE_INT32(RC_MAP_YAW, 4); +PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5); + /** * Sensor readout and publishing. * -- cgit v1.2.3