aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-08 12:34:57 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-08 12:34:57 +0100
commitb93fcca4339edc5312158dc4a70bf8abf2c8bb4b (patch)
tree2dea0af5e1fad2ed2cc88a52abad64f66fffae12 /src/modules
parenta71e6ed3c64d5c1c94d6f5f445b4b746ccf37eff (diff)
downloadpx4-firmware-b93fcca4339edc5312158dc4a70bf8abf2c8bb4b.tar.gz
px4-firmware-b93fcca4339edc5312158dc4a70bf8abf2c8bb4b.tar.bz2
px4-firmware-b93fcca4339edc5312158dc4a70bf8abf2c8bb4b.zip
vehicle cotnrol mode as msg
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp1
-rw-r--r--src/modules/mc_att_control/mc_att_control_base.h1
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h95
3 files changed, 1 insertions, 96 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index e07bcc225..f8399d10b 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -77,6 +77,7 @@
#include <uORB/topics/navigation_capabilities.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_status.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
diff --git a/src/modules/mc_att_control/mc_att_control_base.h b/src/modules/mc_att_control/mc_att_control_base.h
index 6c4b5c707..036dd4c48 100644
--- a/src/modules/mc_att_control/mc_att_control_base.h
+++ b/src/modules/mc_att_control/mc_att_control_base.h
@@ -53,7 +53,6 @@
#include <errno.h>
#include <math.h>
-#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#include <systemlib/perf_counter.h>
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
deleted file mode 100644
index 2dd8550bc..000000000
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ /dev/null
@@ -1,95 +0,0 @@
-/****************************************************************************
- *
- * 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_control_mode.h
- * Definition of the vehicle_control_mode uORB topic.
- *
- * All control apps should depend their actions based on the flags set here.
- *
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- */
-
-#ifndef VEHICLE_CONTROL_MODE
-#define VEHICLE_CONTROL_MODE
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <platforms/px4_defines.h>
-#include "vehicle_status.h"
-
-/**
- * @addtogroup topics @{
- */
-
-
-/**
- * state machine / state of vehicle.
- *
- * Encodes the complete system state and is set by the commander app.
- */
-
-struct vehicle_control_mode_s {
- uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
-
- bool flag_armed;
-
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
-
- // XXX needs yet to be set by state machine helper
- bool flag_system_hil_enabled;
-
- bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_auto_enabled; /**< true if onboard autopilot should act */
- bool flag_control_offboard_enabled; /**< true if offboard control should be used */
- bool flag_control_rates_enabled; /**< true if rates are stabilized */
- bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_force_enabled; /**< true if force control is mixed in */
- bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
- 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_termination_enabled; /**< true if flighttermination is enabled */
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_control_mode);
-
-#endif