aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-02 00:33:36 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-02 00:33:36 +0200
commita9fd5ed90ad67a8081aec3dd3c05034c3d64f81c (patch)
tree74065b07dc620e8e22751563d548a140b17966e4 /src/modules/uORB/topics
parent43b9d96cf4306bc472d16956f5437dbef7c630c0 (diff)
parent4cd66a3242aa2dfb03a3e58ffcc8d27e1350b7ac (diff)
downloadpx4-firmware-a9fd5ed90ad67a8081aec3dd3c05034c3d64f81c.tar.gz
px4-firmware-a9fd5ed90ad67a8081aec3dd3c05034c3d64f81c.tar.bz2
px4-firmware-a9fd5ed90ad67a8081aec3dd3c05034c3d64f81c.zip
Merged master to gnss_rework
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/rc_channels.h68
-rw-r--r--src/modules/uORB/topics/vehicle_status.h4
2 files changed, 30 insertions, 42 deletions
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 370c54442..829d8e57d 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2014 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
@@ -43,59 +43,43 @@
#include "../uORB.h"
/**
- * The number of RC channel inputs supported.
- * Current (Q4/2013) radios support up to 18 channels,
- * leaving at a sane value of 16.
- * This number can be greater then number of RC channels,
- * because single RC channel can be mapped to multiple
- * functions, e.g. for various mode switches.
- */
-#define RC_CHANNELS_MAPPED_MAX 16
-
-/**
* This defines the mapping of the RC functions.
* The value assigned to the specific function corresponds to the entry of
- * the channel array chan[].
+ * the channel array channels[].
*/
enum RC_CHANNELS_FUNCTION {
THROTTLE = 0,
- ROLL = 1,
- PITCH = 2,
- YAW = 3,
- MODE = 4,
- RETURN = 5,
- POSCTL = 6,
- LOITER = 7,
- OFFBOARD_MODE = 8,
- ACRO = 9,
- FLAPS = 10,
- AUX_1 = 11,
- AUX_2 = 12,
- AUX_3 = 13,
- AUX_4 = 14,
- AUX_5 = 15,
- RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
+ ROLL,
+ PITCH,
+ YAW,
+ MODE,
+ RETURN,
+ POSCTL,
+ LOITER,
+ OFFBOARD_MODE,
+ ACRO,
+ FLAPS,
+ AUX_1,
+ AUX_2,
+ AUX_3,
+ AUX_4,
+ AUX_5,
+ RC_CHANNELS_FUNCTION_MAX /**< Indicates the number of functions. There can be more functions than RC channels. */
};
/**
* @addtogroup topics
* @{
*/
-
struct rc_channels_s {
-
- uint64_t timestamp; /**< In microseconds since boot time. */
- uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
- struct {
- float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
- } chan[RC_CHANNELS_MAPPED_MAX];
- uint8_t chan_count; /**< number of valid channels */
-
- /*String array to store the names of the functions*/
- char function_name[RC_CHANNELS_FUNCTION_MAX][20];
- int8_t function[RC_CHANNELS_FUNCTION_MAX];
- uint8_t rssi; /**< Overall receive signal strength */
- bool signal_lost; /**< control signal lost, should be checked together with topic timeout */
+ uint64_t timestamp; /**< Timestamp in microseconds since boot time */
+ uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */
+ float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */
+ uint8_t channel_count; /**< Number of valid channels */
+ char function_name[RC_CHANNELS_FUNCTION_MAX][20]; /**< String array to store the names of the functions */
+ int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */
+ uint8_t rssi; /**< Receive signal strength index */
+ bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */
}; /**< radio control channels. */
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 5dc46dacb..56590047f 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -191,6 +191,8 @@ struct vehicle_status_s {
bool condition_local_altitude_valid;
bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
bool condition_landed; /**< true if vehicle is landed, always true if disarmed */
+ bool condition_power_input_valid; /**< set if input power is valid */
+ float avionics_power_rail_voltage; /**< voltage of the avionics power rail */
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
@@ -220,6 +222,8 @@ struct vehicle_status_s {
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
+
+ bool circuit_breaker_engaged_power_check;
};
/**