forked from Archive/PX4-Autopilot
board_config: remove px4_board_pwr, use px4_shutdown_request instead
px4_board_pwr has become obsolete with the addition of board_shutdown
This commit is contained in:
parent
25dfa9cda6
commit
0165633bf3
|
@ -208,7 +208,7 @@ typedef enum board_power_button_state_notification_e {
|
|||
PWR_BUTTON_REQUEST_SHUT_DOWN, /* Button went up after meeting shutdown button down time */
|
||||
|
||||
PWR_BUTTON_RESPONSE_SHUT_DOWN_PENDING, /* Response from call back board code does nothing the
|
||||
* expectation is that board_do_shutdown will be called.
|
||||
* expectation is that board_shutdown will be called.
|
||||
*/
|
||||
PWR_BUTTON_RESPONSE_SHUT_DOWN_NOW, /* Response from call back board code does shutdown now. */
|
||||
} board_power_button_state_notification_e;
|
||||
|
@ -453,25 +453,16 @@ __EXPORT int board_mcu_version(char *rev, const char **revstr, const char **erra
|
|||
int board_register_power_state_notification_cb(power_button_state_notification_t cb);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_do_shutdown
|
||||
* Name: board_shutdown
|
||||
*
|
||||
* Description:
|
||||
* boards may provide a function to power off the board.
|
||||
*
|
||||
* return - none
|
||||
* return - OK, or -errno
|
||||
*/
|
||||
void board_shutdown(void);
|
||||
int board_shutdown(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: px4_board_pwr
|
||||
*
|
||||
* Description:
|
||||
* boards may provide a function control the power.
|
||||
*
|
||||
* return - none
|
||||
*/
|
||||
#else
|
||||
#define board_register_power_state_notification_cb(cb) (0)
|
||||
#define board_shutdown() { do {} while(0); }
|
||||
#define px4_board_pwr(switch_on) { do {} while(0); }
|
||||
static inline int board_register_power_state_notification_cb(power_button_state_notification_t cb) { return 0; }
|
||||
static inline int board_shutdown(void) { return -EINVAL; }
|
||||
#endif
|
||||
|
|
|
@ -342,16 +342,6 @@ void board_pwr_init(int stage);
|
|||
|
||||
bool board_pwr_button_down(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr
|
||||
*
|
||||
* Description:
|
||||
* Called to turn on or off the TAP
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT bool px4_board_pwr(bool on_not_off);
|
||||
|
||||
#include "../common/board_common.h"
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
|
|
@ -176,24 +176,3 @@ bool board_pwr_button_down(void)
|
|||
{
|
||||
return 0 == stm32_gpioread(KEY_AD_GPIO);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr
|
||||
*
|
||||
* Description:
|
||||
* Called to turn on or off the TAP
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT bool px4_board_pwr(bool on_not_off)
|
||||
{
|
||||
if (on_not_off) {
|
||||
stm32_configgpio(POWER_ON_GPIO);
|
||||
|
||||
} else {
|
||||
|
||||
stm32_configgpio(POWER_OFF_GPIO);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -442,11 +442,6 @@ extern "C" {
|
|||
return sim_delay;
|
||||
}
|
||||
|
||||
bool px4_board_pwr(bool on)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
const char *px4_get_device_names(unsigned int *handle)
|
||||
{
|
||||
return VDev::devList(handle);
|
||||
|
|
|
@ -69,6 +69,7 @@
|
|||
#include <px4_defines.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
#include <px4_shutdown.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_time.h>
|
||||
#include <systemlib/circuit_breaker.h>
|
||||
|
@ -2002,7 +2003,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
*/
|
||||
mavlink_log_critical(&mavlink_log_pub, "USB disconnected, rebooting.")
|
||||
usleep(400000);
|
||||
px4_systemreset(false);
|
||||
px4_shutdown_request(true, false);
|
||||
}
|
||||
|
||||
/* finally judge the USB connected state based on software detection */
|
||||
|
@ -2285,7 +2286,12 @@ int commander_thread_main(int argc, char *argv[])
|
|||
if (!armed.armed) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "DANGEROUSLY LOW BATTERY, SHUT SYSTEM DOWN");
|
||||
usleep(200000);
|
||||
px4_board_pwr(false);
|
||||
int ret_val = px4_shutdown_request(false, false);
|
||||
if (ret_val) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "SYSTEM DOES NOT SUPPORT SHUTDOWN");
|
||||
} else {
|
||||
while(1) { usleep(1); }
|
||||
}
|
||||
|
||||
} else {
|
||||
if (low_bat_action == 2 || low_bat_action == 3) {
|
||||
|
@ -4049,13 +4055,13 @@ void *commander_low_prio_loop(void *arg)
|
|||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub, command_ack);
|
||||
usleep(100000);
|
||||
/* reboot */
|
||||
px4_systemreset(false);
|
||||
px4_shutdown_request(true, false);
|
||||
|
||||
} else if (((int)(cmd.param1)) == 3) {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub, command_ack);
|
||||
usleep(100000);
|
||||
/* reboot to bootloader */
|
||||
px4_systemreset(true);
|
||||
px4_shutdown_request(true, true);
|
||||
|
||||
} else {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub, command_ack);
|
||||
|
|
|
@ -116,7 +116,6 @@ __EXPORT void px4_enable_sim_lockstep(void);
|
|||
__EXPORT void px4_sim_start_delay(void);
|
||||
__EXPORT void px4_sim_stop_delay(void);
|
||||
__EXPORT bool px4_sim_delay_enabled(void);
|
||||
__EXPORT bool px4_board_pwr(bool on);
|
||||
|
||||
__END_DECLS
|
||||
#else
|
||||
|
|
Loading…
Reference in New Issue