aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-04-26 15:13:03 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-04-26 15:13:03 +0200
commit22d3bcdab60c1f788fe76431a02bc9f49601568a (patch)
tree111ec1532c7021b803e386968b2fa6a8a68c11dd /src/modules/uORB/topics
parenta30411e9f2438018a08c0965261067940f88be10 (diff)
parent84943644d77ce21e91fa60a326ab333069333e74 (diff)
downloadpx4-firmware-22d3bcdab60c1f788fe76431a02bc9f49601568a.tar.gz
px4-firmware-22d3bcdab60c1f788fe76431a02bc9f49601568a.tar.bz2
px4-firmware-22d3bcdab60c1f788fe76431a02bc9f49601568a.zip
Merged mpc_rc into ekf_params
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h37
-rw-r--r--src/modules/uORB/topics/optical_flow.h1
-rw-r--r--src/modules/uORB/topics/rc_channels.h3
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h7
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h8
-rw-r--r--src/modules/uORB/topics/vehicle_status.h28
6 files changed, 30 insertions, 54 deletions
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index eac6d6e98..a23d89cd2 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -44,6 +44,16 @@
#include "../uORB.h"
/**
+ * Switch position
+ */
+typedef enum {
+ SWITCH_POS_NONE = 0, /**< switch is not mapped */
+ SWITCH_POS_ON, /**< switch activated (value = 1) */
+ SWITCH_POS_MIDDLE, /**< middle position (value = 0) */
+ SWITCH_POS_OFF /**< switch not activated (value = -1) */
+} switch_pos_t;
+
+/**
* @addtogroup topics
* @{
*/
@@ -51,32 +61,25 @@
struct manual_control_setpoint_s {
uint64_t timestamp;
- float roll; /**< ailerons roll / roll rate input */
- float pitch; /**< elevator / pitch / pitch rate */
- float yaw; /**< rudder / yaw rate / yaw */
- float throttle; /**< throttle / collective thrust / altitude */
-
- float mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- float return_switch; /**< land 2 position switch (mandatory): land, no effect */
- float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
- float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
-
/**
- * Any of the channels below may not be available and be set to NaN
+ * Any of the channels may not be available and be set to NaN
* to indicate that it does not contain valid data.
*/
-
- // XXX needed or parameter?
- //float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
-
- float flaps; /**< flap position */
-
+ float roll; /**< ailerons roll / roll rate input, -1..1 */
+ float pitch; /**< elevator / pitch / pitch rate, -1..1 */
+ float yaw; /**< rudder / yaw rate / yaw, -1..1 */
+ float throttle; /**< throttle / collective thrust / altitude, 0..1 */
+ float flaps; /**< flap position */
float aux1; /**< default function: camera yaw / azimuth */
float aux2; /**< default function: camera pitch / tilt */
float aux3; /**< default function: camera trigger */
float aux4; /**< default function: camera roll */
float aux5; /**< default function: payload drop */
+ switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
+ switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
+ switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
+ switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/optical_flow.h b/src/modules/uORB/topics/optical_flow.h
index 98f0e3fa2..0196ae86b 100644
--- a/src/modules/uORB/topics/optical_flow.h
+++ b/src/modules/uORB/topics/optical_flow.h
@@ -57,6 +57,7 @@ struct optical_flow_s {
uint64_t timestamp; /**< in microseconds since system start */
+ uint64_t flow_timestamp; /**< timestamp from flow sensor */
int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 6eb20efd1..c168b2fac 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -65,7 +65,7 @@ enum RC_CHANNELS_FUNCTION {
MODE = 4,
RETURN = 5,
ASSISTED = 6,
- MISSION = 7,
+ LOITER = 7,
OFFBOARD_MODE = 8,
FLAPS = 9,
AUX_1 = 10,
@@ -94,6 +94,7 @@ struct rc_channels_s {
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 */
}; /**< radio control channels. */
/**
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index adcd028f0..4897ca737 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -63,9 +63,6 @@
struct vehicle_global_position_s {
uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
- bool global_valid; /**< true if position satisfies validity criteria of estimator */
- bool baro_valid; /**< true if baro_alt is valid (vel_d is also valid in this case) */
-
uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
@@ -74,8 +71,8 @@ struct vehicle_global_position_s {
float vel_e; /**< Ground east velocity, m/s */
float vel_d; /**< Ground downside velocity, m/s */
float yaw; /**< Yaw in radians -PI..+PI. */
-
- float baro_alt; /**< Barometric altitude (not raw baro but fused with accelerometer) */
+ float eph;
+ float epv;
};
/**
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index db9637cd9..a15303ea4 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +34,9 @@
/**
* @file vehicle_local_position.h
* Definition of the local fused NED position uORB topic.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef TOPIC_VEHICLE_LOCAL_POSITION_H_
@@ -72,8 +74,8 @@ struct vehicle_local_position_s {
bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */
bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */
uint64_t ref_timestamp; /**< Time when reference position was set */
- int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */
- int32_t ref_lon; /**< Reference point longitude in 1E7 degrees */
+ double ref_lat; /**< Reference point latitude in degrees */
+ double ref_lon; /**< Reference point longitude in degrees */
float ref_alt; /**< Reference altitude AMSL in meters, MUST be set to current (not at reference point!) ground level */
bool landed; /**< true if vehicle is landed */
/* Distance to surface */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 256c5134c..435230432 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -95,29 +95,6 @@ typedef enum {
FAILSAFE_STATE_MAX
} failsafe_state_t;
-typedef enum {
- MODE_SWITCH_MANUAL = 0,
- MODE_SWITCH_ASSISTED,
- MODE_SWITCH_AUTO
-} mode_switch_pos_t;
-
-typedef enum {
- ASSISTED_SWITCH_SEATBELT = 0,
- ASSISTED_SWITCH_EASY
-} assisted_switch_pos_t;
-
-typedef enum {
- RETURN_SWITCH_NONE = 0,
- RETURN_SWITCH_NORMAL,
- RETURN_SWITCH_RETURN
-} return_switch_pos_t;
-
-typedef enum {
- MISSION_SWITCH_NONE = 0,
- MISSION_SWITCH_LOITER,
- MISSION_SWITCH_MISSION
-} mission_switch_pos_t;
-
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
@@ -189,11 +166,6 @@ struct vehicle_status_s {
bool is_rotary_wing;
- mode_switch_pos_t mode_switch;
- return_switch_pos_t return_switch;
- assisted_switch_pos_t assisted_switch;
- mission_switch_pos_t mission_switch;
-
bool condition_battery_voltage_valid;
bool condition_system_in_air_restore; /**< true if we can restore in mid air */
bool condition_system_sensors_initialized;