aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics/manual_control_setpoint.h
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-05-17 11:24:02 +0200
committerJulian Oes <julian@oes.ch>2013-05-17 11:24:02 +0200
commitf5c157e74df12a0cb36b7d27cdad9828d96cc534 (patch)
tree3f758990921a7b52df8afe5131a8298b1141b6f4 /src/modules/uORB/topics/manual_control_setpoint.h
parent80e8eeab2931e79e31adb17c93f5794e666c5763 (diff)
parentfa816d0fd65da461fd5bf8803cf00caebaf23c5c (diff)
downloadpx4-firmware-f5c157e74df12a0cb36b7d27cdad9828d96cc534.tar.gz
px4-firmware-f5c157e74df12a0cb36b7d27cdad9828d96cc534.tar.bz2
px4-firmware-f5c157e74df12a0cb36b7d27cdad9828d96cc534.zip
Merge remote-tracking branch 'upstream/master' into new_state_machine
Conflicts: src/drivers/px4io/px4io.cpp src/modules/commander/commander.c src/modules/commander/state_machine_helper.c
Diffstat (limited to 'src/modules/uORB/topics/manual_control_setpoint.h')
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h88
1 files changed, 88 insertions, 0 deletions
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
new file mode 100644
index 000000000..cfee81ea2
--- /dev/null
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-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
+ * 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 manual_control_setpoint.h
+ * Definition of the manual_control_setpoint uORB topic.
+ */
+
+#ifndef TOPIC_MANUAL_CONTROL_SETPOINT_H_
+#define TOPIC_MANUAL_CONTROL_SETPOINT_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+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 mission_switch; /**< mission 2 position switch (optional): mission, loiter */
+
+ /**
+ * Any of the channels below 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 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 */
+
+}; /**< manual control inputs */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(manual_control_setpoint);
+
+#endif