aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/actuator_direct.h (renamed from src/modules/uORB/topics/rc_channels.h)63
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h16
-rw-r--r--src/modules/uORB/topics/optical_flow.h24
-rw-r--r--src/modules/uORB/topics/test_motor.h2
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h92
-rw-r--r--src/modules/uORB/topics/vehicle_status.h3
6 files changed, 44 insertions, 156 deletions
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/actuator_direct.h
index 16916cc4d..5f9d0f56d 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/actuator_direct.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 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
@@ -32,65 +32,38 @@
****************************************************************************/
/**
- * @file rc_channels.h
- * Definition of the rc_channels uORB topic.
+ * @file actuator_direct.h
*
- * @deprecated DO NOT USE FOR NEW CODE
+ * Actuator direct values.
+ *
+ * Values published to this topic are the direct actuator values which
+ * should be passed to actuators, bypassing mixing
*/
-#ifndef RC_CHANNELS_H_
-#define RC_CHANNELS_H_
+#ifndef TOPIC_ACTUATOR_DIRECT_H
+#define TOPIC_ACTUATOR_DIRECT_H
#include <stdint.h>
#include "../uORB.h"
-/**
- * This defines the mapping of the RC functions.
- * The value assigned to the specific function corresponds to the entry of
- * the channel array channels[].
- */
-enum RC_CHANNELS_FUNCTION {
- THROTTLE = 0,
- ROLL,
- PITCH,
- YAW,
- MODE,
- RETURN,
- POSCTL,
- LOITER,
- OFFBOARD,
- ACRO,
- FLAPS,
- AUX_1,
- AUX_2,
- AUX_3,
- AUX_4,
- AUX_5
-};
-
-// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS
-
-#define RC_CHANNELS_FUNCTION_MAX 18
+#define NUM_ACTUATORS_DIRECT 16
/**
* @addtogroup topics
* @{
*/
-struct rc_channels_s {
- 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 */
- 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. */
+
+struct actuator_direct_s {
+ uint64_t timestamp; /**< timestamp in us since system boot */
+ float values[NUM_ACTUATORS_DIRECT]; /**< actuator values, from -1 to 1 */
+ unsigned nvalues; /**< number of valid values */
+};
/**
* @}
*/
-/* register this as object request broker structure */
-ORB_DECLARE(rc_channels);
+/* actuator direct ORB */
+ORB_DECLARE(actuator_direct);
-#endif
+#endif // TOPIC_ACTUATOR_DIRECT_H
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 15b55648d..13138ebc9 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -47,7 +47,7 @@
* Switch position
*/
typedef enum {
- SWITCH_POS_NONE = 0, /**< switch is not mapped */
+ 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) */
@@ -93,13 +93,13 @@ struct manual_control_setpoint_s {
float aux4; /**< default function: camera roll */
float aux5; /**< default function: payload drop */
- switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
- switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
- switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
- switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
- switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
- switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
-}; /**< manual control inputs */
+ switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
+ switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
+ switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
+ switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
+ switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
+ switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
+};
/**
* @}
diff --git a/src/modules/uORB/topics/optical_flow.h b/src/modules/uORB/topics/optical_flow.h
index 0196ae86b..d3dc46ee0 100644
--- a/src/modules/uORB/topics/optical_flow.h
+++ b/src/modules/uORB/topics/optical_flow.h
@@ -55,16 +55,22 @@
*/
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 */
- float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
- float ground_distance_m; /**< Altitude / distance to ground in meters */
- uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
+ uint64_t timestamp; /**< in microseconds since system start */
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
+ float pixel_flow_x_integral; /**< accumulated optical flow in radians around x axis */
+ float pixel_flow_y_integral; /**< accumulated optical flow in radians around y axis */
+ float gyro_x_rate_integral; /**< accumulated gyro value in radians around x axis */
+ float gyro_y_rate_integral; /**< accumulated gyro value in radians around y axis */
+ float gyro_z_rate_integral; /**< accumulated gyro value in radians around z axis */
+ float ground_distance_m; /**< Altitude / distance to ground in meters */
+ uint32_t integration_timespan; /**<accumulation timespan in microseconds */
+ uint32_t time_since_last_sonar_update;/**< time since last sonar update in microseconds */
+ uint16_t frame_count_since_last_readout;/**< number of accumulated frames in timespan */
+ int16_t gyro_temperature;/**< Temperature * 100 in centi-degrees Celsius */
+ uint8_t quality; /**< Average of quality of accumulated frames, 0: bad quality, 255: maximum quality */
+
+
+
};
diff --git a/src/modules/uORB/topics/test_motor.h b/src/modules/uORB/topics/test_motor.h
index 491096934..2dd90e69d 100644
--- a/src/modules/uORB/topics/test_motor.h
+++ b/src/modules/uORB/topics/test_motor.h
@@ -57,7 +57,7 @@
struct test_motor_s {
uint64_t timestamp; /**< output timestamp in us since system boot */
unsigned motor_number; /**< number of motor to spin */
- float value; /**< output data, in natural output units */
+ float value; /**< output power, range [0..1] */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
deleted file mode 100755
index 1df1433ac..000000000
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ /dev/null
@@ -1,92 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @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
- * 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 vehicle_attitude.h
- * Definition of the attitude uORB topic.
- */
-
-#ifndef VEHICLE_ATTITUDE_H_
-#define VEHICLE_ATTITUDE_H_
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <platforms/px4_defines.h>
-
-/**
- * @addtogroup topics
- * @{
- */
-
-/**
- * Attitude in NED body frame in SI units.
- *
- * @see http://en.wikipedia.org/wiki/International_System_of_Units
- */
-struct vehicle_attitude_s {
-
- uint64_t timestamp; /**< in microseconds since system start */
-
- /* This is similar to the mavlink message ATTITUDE, but for onboard use */
-
- /** @warning roll, pitch and yaw have always to be valid, the rotation matrix and quaternion are optional */
-
- float roll; /**< Roll angle (rad, Tait-Bryan, NED) */
- float pitch; /**< Pitch angle (rad, Tait-Bryan, NED) */
- float yaw; /**< Yaw angle (rad, Tait-Bryan, NED) */
- float rollspeed; /**< Roll angular speed (rad/s, Tait-Bryan, NED) */
- float pitchspeed; /**< Pitch angular speed (rad/s, Tait-Bryan, NED) */
- float yawspeed; /**< Yaw angular speed (rad/s, Tait-Bryan, NED) */
- float rollacc; /**< Roll angular accelration (rad/s, Tait-Bryan, NED) */
- float pitchacc; /**< Pitch angular acceleration (rad/s, Tait-Bryan, NED) */
- float yawacc; /**< Yaw angular acceleration (rad/s, Tait-Bryan, NED) */
- float rate_offsets[3]; /**< Offsets of the body angular rates from zero */
- float R[3][3]; /**< Rotation matrix body to world, (Tait-Bryan, NED) */
- float q[4]; /**< Quaternion (NED) */
- float g_comp[3]; /**< Compensated gravity vector */
- bool R_valid; /**< Rotation matrix valid */
- bool q_valid; /**< Quaternion valid */
-
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_attitude);
-
-#endif
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 8e85b4835..131029061 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -108,7 +108,7 @@ typedef enum {
NAVIGATION_STATE_AUTO_LANDGPSFAIL, /**< Auto land on gps failure (e.g. open loop loiter down) */
NAVIGATION_STATE_ACRO, /**< Acro mode */
NAVIGATION_STATE_LAND, /**< Land mode */
- NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
+ NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
NAVIGATION_STATE_OFFBOARD,
NAVIGATION_STATE_MAX,
@@ -201,6 +201,7 @@ struct vehicle_status_s {
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
+ uint64_t rc_signal_lost_timestamp; /**< Time at which the RC reception was lost */
bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
bool rc_input_blocked; /**< set if RC input should be ignored */