aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-01-06 11:25:17 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-01-06 11:25:17 +0100
commitd3fd3d8219179251d10655944992da75abb8932b (patch)
tree25782ae747ddaacf74d610c9b57627ae46e07f7b /apps/uORB
parent0ef1d6d7529e9c84969ed6f512f733772bba34a0 (diff)
parent8eb8909a3c24c6028e4945e4a057d6d2f27f3d04 (diff)
downloadpx4-firmware-d3fd3d8219179251d10655944992da75abb8932b.tar.gz
px4-firmware-d3fd3d8219179251d10655944992da75abb8932b.tar.bz2
px4-firmware-d3fd3d8219179251d10655944992da75abb8932b.zip
Merged, compiling
Diffstat (limited to 'apps/uORB')
-rw-r--r--apps/uORB/objects_common.cpp3
-rw-r--r--apps/uORB/topics/battery_status.h68
-rw-r--r--apps/uORB/topics/sensor_combined.h4
3 files changed, 73 insertions, 2 deletions
diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp
index dbee15050..2d249a47f 100644
--- a/apps/uORB/objects_common.cpp
+++ b/apps/uORB/objects_common.cpp
@@ -71,6 +71,9 @@ ORB_DEFINE(vehicle_gps_position, struct vehicle_gps_position_s);
#include "topics/vehicle_status.h"
ORB_DEFINE(vehicle_status, struct vehicle_status_s);
+#include "topics/battery_status.h"
+ORB_DEFINE(battery_status, struct battery_status_s);
+
#include "topics/vehicle_global_position.h"
ORB_DEFINE(vehicle_global_position, struct vehicle_global_position_s);
diff --git a/apps/uORB/topics/battery_status.h b/apps/uORB/topics/battery_status.h
new file mode 100644
index 000000000..c40d0d4e5
--- /dev/null
+++ b/apps/uORB/topics/battery_status.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ *
+ * 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 battery_status.h
+ *
+ * Definition of the battery status uORB topic.
+ */
+
+#ifndef BATTERY_STATUS_H_
+#define BATTERY_STATUS_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Battery voltages and status
+ */
+struct battery_status_s {
+ uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
+ float voltage_v; /**< Battery voltage in volts, filtered */
+ float current_a; /**< Battery current in amperes, filtered, -1 if unknown */
+ float discharged_mah; /**< Discharged amount in mAh, filtered, -1 if unknown */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(battery_status);
+
+#endif \ No newline at end of file
diff --git a/apps/uORB/topics/sensor_combined.h b/apps/uORB/topics/sensor_combined.h
index 0324500ac..1d25af35a 100644
--- a/apps/uORB/topics/sensor_combined.h
+++ b/apps/uORB/topics/sensor_combined.h
@@ -99,8 +99,8 @@ struct sensor_combined_s {
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */
float baro_temp_celcius; /**< Temperature in degrees celsius */
- float battery_voltage_v; /**< Battery voltage in volts, filtered */
- float adc_voltage_v[3]; /**< ADC voltages of ADC Chan 11/12/13 or -1 */
+ float adc_voltage_v[4]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
+ float mcu_temp_celcius; /**< Internal temperature measurement of MCU */
uint32_t baro_counter; /**< Number of raw baro measurements taken */
uint32_t battery_voltage_counter; /**< Number of voltage measurements taken */
bool battery_voltage_valid; /**< True if battery voltage can be measured */