aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-06-12 16:51:37 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-06-12 16:51:37 +0200
commit842e7c3df92f5004578f4ae5a7a26300d8a1a419 (patch)
tree744c60b19f1900f3dad86295cfd6341efa5e8af2 /src/modules/uORB
parent2951962c2104a0b2a284a7c5208171b257ed9734 (diff)
parentf4898b94c6fd86d9087ee98634cf543fc1fdcbeb (diff)
downloadpx4-firmware-842e7c3df92f5004578f4ae5a7a26300d8a1a419.tar.gz
px4-firmware-842e7c3df92f5004578f4ae5a7a26300d8a1a419.tar.bz2
px4-firmware-842e7c3df92f5004578f4ae5a7a26300d8a1a419.zip
Merge branch 'navigator_rewrite' into dataman_state_nav_rewrite
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/Publication.cpp2
-rw-r--r--src/modules/uORB/objects_common.cpp6
-rw-r--r--src/modules/uORB/topics/home_position.h5
-rw-r--r--src/modules/uORB/topics/mission.h12
-rw-r--r--src/modules/uORB/topics/mission_result.h1
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h21
-rw-r--r--src/modules/uORB/topics/tecs_status.h92
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h13
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h4
-rw-r--r--src/modules/uORB/topics/vehicle_status.h38
-rw-r--r--src/modules/uORB/topics/wind_estimate.h68
11 files changed, 225 insertions, 37 deletions
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index 5a5981617..cd0b30dd6 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -47,6 +47,7 @@
#include "topics/vehicle_rates_setpoint.h"
#include "topics/actuator_outputs.h"
#include "topics/encoders.h"
+#include "topics/tecs_status.h"
namespace uORB {
@@ -76,5 +77,6 @@ template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
template class __EXPORT Publication<actuator_outputs_s>;
template class __EXPORT Publication<encoders_s>;
+template class __EXPORT Publication<tecs_status_s>;
}
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 90675bb2e..7c3bb0009 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -199,3 +199,9 @@ ORB_DEFINE(encoders, struct encoders_s);
#include "topics/estimator_status.h"
ORB_DEFINE(estimator_status, struct estimator_status_report);
+
+#include "topics/tecs_status.h"
+ORB_DEFINE(tecs_status, struct tecs_status_s);
+
+#include "topics/wind_estimate.h"
+ORB_DEFINE(wind_estimate, struct wind_estimate_s);
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
index 08d11abae..70071130d 100644
--- a/src/modules/uORB/topics/home_position.h
+++ b/src/modules/uORB/topics/home_position.h
@@ -59,10 +59,13 @@ struct home_position_s
{
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
- //bool altitude_is_relative; // TODO what means home relative altitude? we need clear definition of reference altitude then
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
float alt; /**< Altitude in meters */
+
+ float x; /**< X coordinate in meters */
+ float y; /**< Y coordinate in meters */
+ float z; /**< Z coordinate in meters */
};
/**
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 5f3cbcb1d..4bcaaaa5a 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 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
@@ -37,6 +34,9 @@
/**
* @file mission.h
* Definition of a mission consisting of mission items.
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_MISSION_H_
@@ -58,7 +58,8 @@ enum NAV_CMD {
NAV_CMD_LAND=21,
NAV_CMD_TAKEOFF=22,
NAV_CMD_ROI=80,
- NAV_CMD_PATHPLANNING=81
+ NAV_CMD_PATHPLANNING=81,
+ NAV_CMD_DO_JUMP=177
};
enum ORIGIN {
@@ -91,6 +92,9 @@ struct mission_item_s {
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
bool autocontinue; /**< true if next waypoint should follow after this one */
enum ORIGIN origin; /**< where the waypoint has been generated */
+ int do_jump_mission_index; /**< index where the do jump will go to */
+ unsigned do_jump_repeat_count; /**< how many times do jump needs to be done */
+ unsigned do_jump_current_count; /**< count how many times the jump has been done */
};
struct mission_s
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index 7c3921198..ad654a9ff 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -56,6 +56,7 @@ struct mission_result_s
bool mission_reached; /**< true if mission has been reached */
unsigned mission_index_reached; /**< index of the mission which has been reached */
unsigned index_current_mission; /**< index of the current mission */
+ bool mission_finished; /**< true if mission has been completed */
};
/**
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 34aaa30dd..ce42035ba 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 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
@@ -37,6 +34,10 @@
/**
* @file mission_item_triplet.h
* Definition of the global WGS84 position setpoint uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_MISSION_ITEM_TRIPLET_H_
@@ -45,7 +46,6 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
/**
* @addtogroup topics
@@ -54,11 +54,12 @@
enum SETPOINT_TYPE
{
- SETPOINT_TYPE_NORMAL = 0, /**< normal setpoint */
- SETPOINT_TYPE_LOITER, /**< loiter setpoint */
- SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
- SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, vehicle must descend until landing */
- SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
+ SETPOINT_TYPE_POSITION = 0, /**< position setpoint */
+ SETPOINT_TYPE_VELOCITY, /**< velocity setpoint */
+ SETPOINT_TYPE_LOITER, /**< loiter setpoint */
+ SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
+ SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */
+ SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
};
struct position_setpoint_s
@@ -84,8 +85,6 @@ struct position_setpoint_triplet_s
struct position_setpoint_s previous;
struct position_setpoint_s current;
struct position_setpoint_s next;
-
- nav_state_t nav_state; /**< navigation state */
};
/**
diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h
new file mode 100644
index 000000000..05310e906
--- /dev/null
+++ b/src/modules/uORB/topics/tecs_status.h
@@ -0,0 +1,92 @@
+/****************************************************************************
+ *
+ * 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
+ * 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_global_position.h
+ * Definition of the global fused WGS84 position uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ */
+
+#ifndef TECS_STATUS_T_H_
+#define TECS_STATUS_T_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+typedef enum {
+ TECS_MODE_NORMAL,
+ TECS_MODE_UNDERSPEED,
+ TECS_MODE_TAKEOFF,
+ TECS_MODE_LAND,
+ TECS_MODE_LAND_THROTTLELIM
+} tecs_mode;
+
+ /**
+ * Internal values of the (m)TECS fixed wing speed alnd altitude control system
+ */
+struct tecs_status_s {
+ uint64_t timestamp; /**< timestamp, in microseconds since system start */
+
+ float altitudeSp;
+ float altitude;
+ float flightPathAngleSp;
+ float flightPathAngle;
+ float airspeedSp;
+ float airspeed;
+ float airspeedFiltered;
+ float airspeedDerivativeSp;
+ float airspeedDerivative;
+
+ float totalEnergyRateSp;
+ float totalEnergyRate;
+ float energyDistributionRateSp;
+ float energyDistributionRate;
+
+ tecs_mode mode;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(tecs_status);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index 4897ca737..e32529cb4 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -36,7 +36,7 @@
* Definition of the global fused WGS84 position uORB topic.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
@@ -61,15 +61,14 @@
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
*/
struct vehicle_global_position_s {
- uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
-
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
float alt; /**< Altitude AMSL in meters */
- float vel_n; /**< Ground north velocity, m/s */
- float vel_e; /**< Ground east velocity, m/s */
- float vel_d; /**< Ground downside velocity, m/s */
+ float vel_n; /**< Ground north velocity, m/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 eph;
float epv;
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 5924a324d..bbacb733a 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -65,8 +65,8 @@ struct vehicle_gps_position_s {
float c_variance_rad; /**< course accuracy estimate rad */
uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
- float eph_m; /**< GPS HDOP horizontal dilution of position in m */
- float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ float eph; /**< GPS HDOP horizontal dilution of position in m */
+ float epv; /**< GPS VDOP horizontal dilution of position in m */
unsigned noise_per_ms; /**< */
unsigned jamming_indicator; /**< */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index ea20a317a..259d7329e 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -54,8 +54,6 @@
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
-
/**
* @addtogroup topics @{
*/
@@ -65,9 +63,11 @@ typedef enum {
MAIN_STATE_MANUAL = 0,
MAIN_STATE_ALTCTL,
MAIN_STATE_POSCTL,
- MAIN_STATE_AUTO,
+ MAIN_STATE_AUTO_MISSION,
+ MAIN_STATE_AUTO_LOITER,
+ MAIN_STATE_AUTO_RTL,
MAIN_STATE_ACRO,
- MAIN_STATE_MAX
+ MAIN_STATE_MAX,
} main_state_t;
// If you change the order, add or remove arming_state_t states make sure to update the arrays
@@ -80,7 +80,7 @@ typedef enum {
ARMING_STATE_STANDBY_ERROR,
ARMING_STATE_REBOOT,
ARMING_STATE_IN_AIR_RESTORE,
- ARMING_STATE_MAX
+ ARMING_STATE_MAX,
} arming_state_t;
typedef enum {
@@ -90,12 +90,27 @@ typedef enum {
typedef enum {
FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
- FAILSAFE_STATE_RTL, /**< Return To Launch */
- FAILSAFE_STATE_LAND, /**< Land without position control */
+ FAILSAFE_STATE_RTL_RC, /**< Return To Launch on remote control loss */
+ FAILSAFE_STATE_RTL_DL, /**< Return To Launch on datalink loss */
+ FAILSAFE_STATE_LAND, /**< Land as safe as possible */
FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
- FAILSAFE_STATE_MAX
+ FAILSAFE_STATE_MAX,
} failsafe_state_t;
+typedef enum {
+ NAVIGATION_STATE_MANUAL = 0,
+ NAVIGATION_STATE_ACRO,
+ NAVIGATION_STATE_ALTCTL,
+ NAVIGATION_STATE_POSCTL,
+ NAVIGATION_STATE_AUTO_MISSION,
+ NAVIGATION_STATE_AUTO_LOITER,
+ NAVIGATION_STATE_AUTO_RTL,
+ NAVIGATION_STATE_AUTO_RTL_RC,
+ NAVIGATION_STATE_AUTO_RTL_DL,
+ NAVIGATION_STATE_LAND,
+ NAVIGATION_STATE_TERMINATION,
+} navigation_state_t;
+
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
@@ -154,11 +169,10 @@ struct vehicle_status_s {
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
- main_state_t main_state; /**< main state machine */
- unsigned int set_nav_state; /**< set navigation state machine to specified value */
- uint64_t set_nav_state_timestamp; /**< timestamp of latest change of set_nav_state */
+ main_state_t main_state; /**< main state machine */
+ navigation_state_t set_nav_state; /**< set navigation state machine to specified value */
arming_state_t arming_state; /**< current arming state */
- hil_state_t hil_state; /**< current hil state */
+ hil_state_t hil_state; /**< current hil state */
failsafe_state_t failsafe_state; /**< current failsafe state */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
diff --git a/src/modules/uORB/topics/wind_estimate.h b/src/modules/uORB/topics/wind_estimate.h
new file mode 100644
index 000000000..58333a64f
--- /dev/null
+++ b/src/modules/uORB/topics/wind_estimate.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (c) 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
+ * 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 wind_estimate.h
+ *
+ * Wind estimate topic topic
+ *
+ */
+
+#ifndef TOPIC_WIND_ESTIMATE_H
+#define TOPIC_WIND_ESTIMATE_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/** Wind estimate */
+struct wind_estimate_s {
+
+ uint64_t timestamp; /**< Microseconds since system boot */
+ float windspeed_north; /**< Wind component in north / X direction */
+ float windspeed_east; /**< Wind component in east / Y direction */
+ float covariance_north; /**< Uncertainty - set to zero (no uncertainty) if not estimated */
+ float covariance_east; /**< Uncertainty - set to zero (no uncertainty) if not estimated */
+};
+
+/**
+ * @}
+ */
+
+ORB_DECLARE(wind_estimate);
+
+#endif \ No newline at end of file