aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/state_machine_helper.h
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-06 23:43:09 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-06 23:43:09 +0200
commit7f2a63eb964b384a6b76e7004f1250d705f35fb0 (patch)
tree2af4ef8e8057838ce74d29371c48fc3090c8dc2a /apps/commander/state_machine_helper.h
parentf88bba0cec9fa98037a966e2e3bcac8ad10b68f0 (diff)
downloadpx4-firmware-7f2a63eb964b384a6b76e7004f1250d705f35fb0.tar.gz
px4-firmware-7f2a63eb964b384a6b76e7004f1250d705f35fb0.tar.bz2
px4-firmware-7f2a63eb964b384a6b76e7004f1250d705f35fb0.zip
Completed calibration state machine, calibration state now propagating to sensor, scale calibration soon
Diffstat (limited to 'apps/commander/state_machine_helper.h')
-rw-r--r--apps/commander/state_machine_helper.h52
1 files changed, 28 insertions, 24 deletions
diff --git a/apps/commander/state_machine_helper.h b/apps/commander/state_machine_helper.h
index 0abc6349c..540182e4f 100644
--- a/apps/commander/state_machine_helper.h
+++ b/apps/commander/state_machine_helper.h
@@ -4,7 +4,6 @@
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
*
- *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -34,7 +33,10 @@
*
****************************************************************************/
-/* @file State machine helper functions definitions */
+/**
+ * @file state_machine_helper.h
+ * State machine helper functions definitions
+ */
#ifndef STATE_MACHINE_HELPER_H_
#define STATE_MACHINE_HELPER_H_
@@ -47,14 +49,13 @@
#include <v1.0/common/mavlink.h>
-/*
- * @brief switch to new state with no checking *
+/**
+ * Switch to new state with no checking.
*
* do_state_update: this is the functions that all other functions have to call in order to update the state.
* the function does not question the state change, this must be done before
* The function performs actions that are connected with the new state (buzzer, reboot, ...)
*
- *
*/
void do_state_update(int status_pub, struct vehicle_status_s *current_status, commander_state_machine_t new_state);
@@ -69,42 +70,45 @@ void do_state_update(int status_pub, struct vehicle_status_s *current_status, co
// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-/*
- * @brief handle state machine if got position fix
+/**
+ * Handle state machine if got position fix
*/
void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if position fix lost
+/**
+ * Handle state machine if position fix lost
*/
void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if user wants to arm
+/**
+ * Handle state machine if user wants to arm
*/
void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if user wants to disarm
+/**
+ * Handle state machine if user wants to disarm
*/
void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if mode switch is manual
+/**
+ * Handle state machine if mode switch is manual
*/
void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if mode switch is stabilized
+/**
+ * Handle state machine if mode switch is stabilized
*/
void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status);
-/*
- * @brief handle state machine if mode switch is auto
+/**
+ * Handle state machine if mode switch is auto
*/
void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status);
-
+/**
+ * Publish current state information
+ */
+void state_machine_publish(int status_pub, struct vehicle_status_s *current_status);
/*
@@ -113,13 +117,13 @@ void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *cur
*
*/
-/*
- * @brief handles *incoming request* to switch to a specific state, if state change is successful returns 0
+/**
+ * Handles *incoming request* to switch to a specific state, if state change is successful returns 0
*/
uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, uint8_t mode);
-/*
- * @brief handles *incoming request* to switch to a specific custom state, if state change is successful returns 0
+/**
+ * Handles *incoming request* to switch to a specific custom state, if state change is successful returns 0
*/
uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, uint8_t custom_mode);