aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
Diffstat (limited to 'apps')
-rw-r--r--apps/commander/commander.c3
-rw-r--r--apps/drivers/px4io/px4io.cpp3
-rw-r--r--apps/mathlib/CMSIS/Makefile2
-rw-r--r--apps/uORB/topics/vehicle_status.h8
4 files changed, 14 insertions, 2 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 17087ab8a..986266843 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -1200,6 +1200,7 @@ int commander_thread_main(int argc, char *argv[])
/* 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;
+ current_status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
/* advertise to ORB */
stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
@@ -1393,6 +1394,7 @@ int commander_thread_main(int argc, char *argv[])
if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) {
low_battery_voltage_actions_done = true;
+ current_status.battery_warning = VEHICLE_BATTERY_WARNING_WARNING;
mavlink_log_critical(mavlink_fd, "[commander] WARNING! LOW BATTERY!");
}
@@ -1403,6 +1405,7 @@ int commander_thread_main(int argc, char *argv[])
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;
+ current_status.battery_warning = VEHICLE_BATTERY_WARNING_ALERT;
mavlink_log_critical(mavlink_fd, "[commander] EMERGENCY! CRITICAL BATTERY!");
state_machine_emergency(stat_pub, &current_status, mavlink_fd);
}
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index 82ff61808..fd531a327 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -388,7 +388,8 @@ PX4IO::task_main()
if (fds[1].revents & POLLIN) {
/* get controls */
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
+ orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1), _t_actuators, &_controls);
/* scale controls to PWM (temporary measure) */
for (unsigned i = 0; i < _max_actuators; i++)
diff --git a/apps/mathlib/CMSIS/Makefile b/apps/mathlib/CMSIS/Makefile
index 0b6794470..fa5de668a 100644
--- a/apps/mathlib/CMSIS/Makefile
+++ b/apps/mathlib/CMSIS/Makefile
@@ -38,7 +38,7 @@
#
# Find sources
#
-DSPLIB_SRCDIR = $(dir $(lastword $(MAKEFILE_LIST)))
+DSPLIB_SRCDIR := $(dir $(lastword $(MAKEFILE_LIST)))
CSRCS := $(wildcard $(DSPLIB_SRCDIR)/DSP_Lib/Source/*/*.c)
INCLUDES += $(DSPLIB_SRCDIR)/Include \
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 23172d7cf..75c9ea0fc 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -99,6 +99,13 @@ enum VEHICLE_ATTITUDE_MODE {
VEHICLE_ATTITUDE_MODE_ATTITUDE /**< tait-bryan attitude control mode */
};
+enum VEHICLE_BATTERY_WARNING {
+ VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
+ VEHICLE_BATTERY_WARNING_WARNING, /**< warning of low voltage 1. stage */
+ VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
+};
+
+
/**
* state machine / state of vehicle.
*
@@ -157,6 +164,7 @@ struct vehicle_status_s
float voltage_battery;
float current_battery;
float battery_remaining;
+ enum VEHICLE_BATTERY_WARNING battery_warning; /**< current battery warning mode, as defined by VEHICLE_BATTERY_WARNING enum */
uint16_t drop_rate_comm;
uint16_t errors_comm;
uint16_t errors_count1;