aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorilya <ilja@Ilyas-MacBook-Pro.local>2014-10-26 15:00:41 +0200
committerilya <ilja@Ilyas-MacBook-Pro.local>2014-10-26 15:00:41 +0200
commit1f88f5d5bf3fa73f66907be8e654f9a8a06f88e8 (patch)
treebbf592b955858037a64f66868e23e19eeed3eaa7
parent9b27f16fc566f8dcc3ce23b5acddb86a2e4ac7fb (diff)
downloadpx4-firmware-1f88f5d5bf3fa73f66907be8e654f9a8a06f88e8.tar.gz
px4-firmware-1f88f5d5bf3fa73f66907be8e654f9a8a06f88e8.tar.bz2
px4-firmware-1f88f5d5bf3fa73f66907be8e654f9a8a06f88e8.zip
Changes in uORB
-rw-r--r--src/modules/uORB/objects_common.cpp9
-rw-r--r--src/modules/uORB/topics/commander_request.h84
-rw-r--r--src/modules/uORB/topics/external_trajectory.h37
-rw-r--r--src/modules/uORB/topics/trajectory.h33
-rw-r--r--src/modules/uORB/topics/vehicle_command.h27
-rw-r--r--src/modules/uORB/topics/vehicle_status.h27
6 files changed, 203 insertions, 14 deletions
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index e92dab4bc..945934630 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -248,3 +248,12 @@ ORB_DEFINE(get_drone_parameter, struct get_drone_param_s);
#include "topics/pass_drone_parameter.h"
ORB_DEFINE(pass_drone_parameter, struct pass_drone_param_s);
+
+#include "topics/commander_request.h"
+ORB_DEFINE(commander_request, struct commander_request_s);
+
+#include "topics/trajectory.h"
+ORB_DEFINE(trajectory, struct trajectory_s);
+
+#include "topics/external_trajectory.h"
+ORB_DEFINE(external_trajectory, struct external_trajectory_s);
diff --git a/src/modules/uORB/topics/commander_request.h b/src/modules/uORB/topics/commander_request.h
new file mode 100644
index 000000000..5063e894b
--- /dev/null
+++ b/src/modules/uORB/topics/commander_request.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * 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 commander_request.h
+ * Definition of the commander_request uORB topic.
+ *
+ * Commander_requests are requests to commander for vehicle status changes.
+ *
+ * Commander is the responsible app for managing system related tasks
+ * and setting vehicle statuses other apps must make request for commander
+ * if system related task or system state change is needed.
+ *
+ * Commander will process this request and decide what to do with it.
+ *
+ * @author Martins Frolovs <martins.f@airdog.com>
+ */
+
+#ifndef COMMANDER_REQUEST_H_
+#define COMMANDER_REQUEST_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+#include "vehicle_status.h"
+
+/**
+ * @addtogroup topics @{
+ */
+
+/**
+ * Request type.
+ */
+typedef enum {
+ V_MAIN_STATE_CHANGE = 0,
+ V_DISARM,
+ V_NAVIGATION_STATE_CHANGE
+} request_type_t;
+
+struct commander_request_s {
+ request_type_t request_type;
+
+ main_state_t main_state;
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(commander_request);
+
+#endif
diff --git a/src/modules/uORB/topics/external_trajectory.h b/src/modules/uORB/topics/external_trajectory.h
new file mode 100644
index 000000000..a2830abd7
--- /dev/null
+++ b/src/modules/uORB/topics/external_trajectory.h
@@ -0,0 +1,37 @@
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+ /**
+ *
+ */
+struct external_trajectory_s {
+ uint8_t point_type; /**< Indicates whether movement has crossed the threshold, 0 - still point, 1 - moving */
+ uint8_t sysid; /**< External system id */
+
+ // GPOS fields follow
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
+ double lat; /**< Latitude in degrees */
+ double lon; /**< Longitude in degrees */
+ // TODO! Check if AMSL or WGS84
+ float alt; /**< Altitude AMSL in meters */
+ float relative_alt; /**< Altitude above ground 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 heading; /**< Compass heading in radians [0..2PI) */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(external_trajectory);
diff --git a/src/modules/uORB/topics/trajectory.h b/src/modules/uORB/topics/trajectory.h
new file mode 100644
index 000000000..0a6b58856
--- /dev/null
+++ b/src/modules/uORB/topics/trajectory.h
@@ -0,0 +1,33 @@
+#pragma once
+
+#include <stdint.h>
+#include <sys/types.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+// TODO! Currently set to mirror a bit the trajectory message. Consider different structure
+struct trajectory_s {
+ uint8_t point_type; /**< Indicates whether movement has crossed the threshold, 0 - still point, 1 - moving */
+
+ // GPOS fields follow
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
+ double lat; /**< Latitude in degrees */
+ double lon; /**< Longitude in degrees */
+ // TODO! Check if AMSL or WGS84
+ float alt; /**< Altitude AMSL in meters */
+ float relative_alt; /**< Altitude above ground 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 heading; /**< Compass heading in radians [0..2PI) */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(trajectory);
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index f264accbb..b1d076c80 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -1,6 +1,9 @@
/****************************************************************************
*
- * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
+ * 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
@@ -68,6 +71,7 @@ enum VEHICLE_CMD {
VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_REMOTE_CMD = 94, /* Handle command from Remote |ENUM REMOTE_CMD| Empty| Empty| Empty| Empty| Empty */
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
@@ -95,7 +99,8 @@ enum VEHICLE_CMD {
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */
- VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */
+ VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002, /**< Control a pre-programmed payload deployment */
+ VEHICLE_CMD_ENUM_END = 50001, /* | */
};
/**
@@ -114,6 +119,24 @@ enum VEHICLE_CMD_RESULT {
};
/**
+ * Commands for airleash.
+ *
+ */
+enum REMOTE_CMD {
+ REMOTE_CMD_TAKEOFF = 0,
+ REMOTE_CMD_PLAY_PAUSE = 1,
+ REMOTE_CMD_COME_TO_ME = 2,
+ REMOTE_CMD_UP = 3,
+ REMOTE_CMD_DOWN = 4,
+ REMOTE_CMD_LEFT = 5,
+ REMOTE_CMD_RIGHT = 6,
+ REMOTE_CMD_FURTHER = 7,
+ REMOTE_CMD_CLOSER = 8,
+ REMOTE_CMD_LAND_DISARM = 9,
+ REMOTE_CMD_LOOK_DOWN = 10
+};
+
+/**
* @addtogroup topics
* @{
*/
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 38c147a4b..7cbdaa3b3 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -69,6 +69,7 @@ typedef enum {
MAIN_STATE_AUTO_MISSION,
MAIN_STATE_AUTO_LOITER,
MAIN_STATE_AUTO_RTL,
+ MAIN_STATE_AUTO_ABS_FOLLOW,
MAIN_STATE_ACRO,
MAIN_STATE_OFFBOARD,
MAIN_STATE_FOLLOW,
@@ -98,21 +99,22 @@ typedef enum {
*/
typedef enum {
NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
- NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
- NAVIGATION_STATE_POSCTL, /**< Position control mode */
+ NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
+ NAVIGATION_STATE_POSCTL, /**< Position control mode */
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
- NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
+ NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
NAVIGATION_STATE_AUTO_RCRECOVER, /**< RC recover mode */
- NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
+ NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
+ NAVIGATION_STATE_AUTO_ABS_FOLLOW, /**< AUTO Abs Follow mode */
NAVIGATION_STATE_AUTO_LANDENGFAIL, /**< Auto land on engine failure */
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_ACRO, /**< Acro mode */
+ NAVIGATION_STATE_LAND, /**< Land mode */
NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
NAVIGATION_STATE_OFFBOARD,
- NAVIGATION_STATE_FOLLOW, /**< Manual-controlled follow mode */
+ NAVIGATION_STATE_FOLLOW, /**< Manual-controlled follow mode */
NAVIGATION_STATE_MAX,
} navigation_state_t;
@@ -154,8 +156,9 @@ enum VEHICLE_TYPE {
enum VEHICLE_BATTERY_WARNING {
VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
- VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
- VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
+ VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
+ VEHICLE_BATTERY_WARNING_CRITICAL, /**< alerting of critical voltage */
+ VEHICLE_BATTERY_WARNING_FLAT /**< alerting of flat battery */
};
/**
@@ -175,10 +178,10 @@ struct vehicle_status_s {
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 */
- navigation_state_t nav_state; /**< set navigation state machine to specified value */
+ navigation_state_t 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 */
- bool failsafe; /**< true if system is in failsafe state */
+ hil_state_t hil_state; /**< current hil state */
+ bool failsafe; /**< true if system is in failsafe state */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */