aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/objects_common.cpp11
-rw-r--r--src/modules/uORB/topics/fence.h80
-rw-r--r--src/modules/uORB/topics/mission.h35
-rw-r--r--src/modules/uORB/topics/mission_item_triplet.h (renamed from src/modules/uORB/topics/vehicle_global_position_set_triplet.h)29
-rw-r--r--src/modules/uORB/topics/mission_result.h67
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_status.h8
7 files changed, 202 insertions, 29 deletions
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c6a252b55..7434df1c3 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -120,14 +120,21 @@ ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setp
#include "topics/vehicle_global_position_setpoint.h"
ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
-#include "topics/vehicle_global_position_set_triplet.h"
-ORB_DEFINE(vehicle_global_position_set_triplet, struct vehicle_global_position_set_triplet_s);
+#include "topics/mission_item_triplet.h"
+ORB_DEFINE(mission_item_triplet, struct mission_item_triplet_s);
#include "topics/vehicle_global_velocity_setpoint.h"
ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
#include "topics/mission.h"
ORB_DEFINE(mission, struct mission_s);
+ORB_DEFINE(onboard_mission, struct mission_s);
+
+#include "topics/mission_result.h"
+ORB_DEFINE(mission_result, struct mission_result_s);
+
+#include "topics/fence.h"
+ORB_DEFINE(fence, unsigned);
#include "topics/vehicle_attitude_setpoint.h"
ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
diff --git a/src/modules/uORB/topics/fence.h b/src/modules/uORB/topics/fence.h
new file mode 100644
index 000000000..6f16c51cf
--- /dev/null
+++ b/src/modules/uORB/topics/fence.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
+ *
+ * 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 fence.h
+ * Definition of geofence.
+ */
+
+#ifndef TOPIC_FENCE_H_
+#define TOPIC_FENCE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+#define GEOFENCE_MAX_VERTICES 16
+
+/**
+ * This is the position of a geofence vertex
+ *
+ */
+struct fence_vertex_s {
+ // Worst case float precision gives us 2 meter resolution at the equator
+ float lat; /**< latitude in degrees */
+ float lon; /**< longitude in degrees */
+};
+
+/**
+ * This is the position of a geofence
+ *
+ */
+struct fence_s {
+ unsigned count; /**< number of actual vertices */
+ struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES];
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(fence);
+
+#endif
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 978a3383a..2427a1d57 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -35,8 +35,8 @@
****************************************************************************/
/**
- * @file mission_item.h
- * Definition of one mission item.
+ * @file mission.h
+ * Definition of a mission consisting of mission items.
*/
#ifndef TOPIC_MISSION_H_
@@ -46,14 +46,17 @@
#include <stdbool.h>
#include "../uORB.h"
+/* compatible to mavlink MAV_CMD */
enum NAV_CMD {
- NAV_CMD_WAYPOINT = 0,
- NAV_CMD_LOITER_TURN_COUNT,
- NAV_CMD_LOITER_TIME_LIMIT,
- NAV_CMD_LOITER_UNLIMITED,
- NAV_CMD_RETURN_TO_LAUNCH,
- NAV_CMD_LAND,
- NAV_CMD_TAKEOFF
+ NAV_CMD_WAYPOINT=16,
+ NAV_CMD_LOITER_UNLIMITED=17,
+ NAV_CMD_LOITER_TURN_COUNT=18,
+ NAV_CMD_LOITER_TIME_LIMIT=19,
+ NAV_CMD_RETURN_TO_LAUNCH=20,
+ NAV_CMD_LAND=21,
+ NAV_CMD_TAKEOFF=22,
+ NAV_CMD_ROI=80,
+ NAV_CMD_PATHPLANNING=81
};
/**
@@ -75,18 +78,19 @@ struct mission_item_s
float altitude; /**< altitude in meters */
float yaw; /**< in radians NED -PI..+PI */
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
- uint8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
- enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
- float param1;
- float param2;
- float param3;
- float param4;
+ int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
+ enum NAV_CMD nav_cmd; /**< navigation command */
+ float radius; /**< radius in which the mission is accepted as reached in meters */
+ float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
+ bool autocontinue; /**< true if next waypoint should follow after this one */
+ int index; /**< index matching the mavlink waypoint */
};
struct mission_s
{
struct mission_item_s *items;
unsigned count;
+ int current_index; /**< default -1, start at the one changed latest */
};
/**
@@ -95,5 +99,6 @@ struct mission_s
/* register this as object request broker structure */
ORB_DECLARE(mission);
+ORB_DECLARE(onboard_mission);
#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/mission_item_triplet.h
index 8516b263f..b35eae607 100644
--- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
+++ b/src/modules/uORB/topics/mission_item_triplet.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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>
@@ -35,18 +35,18 @@
****************************************************************************/
/**
- * @file vehicle_global_position_setpoint.h
+ * @file mission_item_triplet.h
* Definition of the global WGS84 position setpoint uORB topic.
*/
-#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
-#define TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
+#ifndef TOPIC_MISSION_ITEM_TRIPLET_H_
+#define TOPIC_MISSION_ITEM_TRIPLET_H_
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include "vehicle_global_position_setpoint.h"
+#include "mission.h"
/**
* @addtogroup topics
@@ -58,14 +58,19 @@
*
* This are the three next waypoints (or just the next two or one).
*/
-struct vehicle_global_position_set_triplet_s
+struct mission_item_triplet_s
{
- bool previous_valid; /**< flag indicating previous position is valid */
- bool next_valid; /**< flag indicating next position is valid */
+ bool previous_valid;
+ bool current_valid; /**< flag indicating previous mission item is valid */
+ bool next_valid; /**< flag indicating next mission item is valid */
- struct vehicle_global_position_setpoint_s previous;
- struct vehicle_global_position_setpoint_s current;
- struct vehicle_global_position_setpoint_s next;
+ struct mission_item_s previous;
+ struct mission_item_s current;
+ struct mission_item_s next;
+
+ int previous_index;
+ int current_index;
+ int next_index;
};
/**
@@ -73,6 +78,6 @@ struct vehicle_global_position_set_triplet_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(vehicle_global_position_set_triplet);
+ORB_DECLARE(mission_item_triplet);
#endif
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
new file mode 100644
index 000000000..c99706b97
--- /dev/null
+++ b/src/modules/uORB/topics/mission_result.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 mission_result.h
+ * Mission results that navigator needs to pass on to commander and mavlink.
+ */
+
+#ifndef TOPIC_MISSION_RESULT_H
+#define TOPIC_MISSION_RESULT_H
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct mission_result_s
+{
+ bool mission_reached; /**< true if mission has been reached */
+ unsigned mission_index; /**< index of the mission which has been reached */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(mission_result);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 38fb74c9b..e26fb97c8 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -78,6 +78,7 @@ struct vehicle_control_mode_s
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
+ bool flag_control_flighttermination_enabled; /**< true if flighttermination is enabled */
bool flag_control_auto_enabled; // TEMP
uint8_t auto_state; // TEMP navigation state for AUTO modes
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1c184d3a7..1c3763924 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -95,6 +95,12 @@ typedef enum {
HIL_STATE_ON
} hil_state_t;
+
+typedef enum {
+ FLIGHTTERMINATION_STATE_OFF = 0,
+ FLIGHTTERMINATION_STATE_ON
+} flighttermination_state_t;
+
typedef enum {
MODE_SWITCH_MANUAL = 0,
MODE_SWITCH_ASSISTED,
@@ -229,6 +235,8 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
+
+ flighttermination_state_t flighttermination_state;
};
/**