mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-04 22:17:01 +08:00
[commands] merging rotorcraft and fixedwing commands
- all commands are now in pprz_t type (int16_t) - should not be a problem since all commands are already scaled at pprz format
This commit is contained in:
@@ -60,7 +60,7 @@ stm_passthrough.srcs += $(SRC_LISA)/lisa_overo_link.c \
|
|||||||
stm_passthrough.srcs += math/pprz_trig_int.c
|
stm_passthrough.srcs += math/pprz_trig_int.c
|
||||||
stm_passthrough.srcs += lisa/plug_sys.c
|
stm_passthrough.srcs += lisa/plug_sys.c
|
||||||
|
|
||||||
stm_passthrough.srcs += $(SRC_FIRMWARE)/commands.c
|
stm_passthrough.srcs += subsystems/commands.c
|
||||||
|
|
||||||
# Radio control
|
# Radio control
|
||||||
#
|
#
|
||||||
|
|||||||
@@ -508,7 +508,7 @@ test_actuators_mkk.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
|||||||
test_actuators_mkk.srcs += $(COMMON_TELEMETRY_SRCS)
|
test_actuators_mkk.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||||
|
|
||||||
test_actuators_mkk.srcs += test/test_actuators.c
|
test_actuators_mkk.srcs += test/test_actuators.c
|
||||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/commands.c
|
test_actuators_mkk.srcs += subsystems/commands.c
|
||||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
|
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c
|
||||||
test_actuators_mkk.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c1
|
test_actuators_mkk.CFLAGS += -DACTUATORS_MKK_DEVICE=i2c1
|
||||||
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
|
test_actuators_mkk.srcs += $(SRC_FIRMWARE)/actuators/supervision.c
|
||||||
@@ -526,7 +526,7 @@ test_actuators_asctecv1.CFLAGS += $(COMMON_TELEMETRY_CFLAGS)
|
|||||||
test_actuators_asctecv1.srcs += $(COMMON_TELEMETRY_SRCS)
|
test_actuators_asctecv1.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||||
|
|
||||||
test_actuators_asctecv1.srcs += test/test_actuators.c
|
test_actuators_asctecv1.srcs += test/test_actuators.c
|
||||||
test_actuators_asctecv1.srcs += $(SRC_FIRMWARE)/commands.c
|
test_actuators_asctecv1.srcs += subsystems/commands.c
|
||||||
test_actuators_asctecv1.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c1
|
test_actuators_asctecv1.CFLAGS += -DACTUATORS_ASCTEC_DEVICE=i2c1
|
||||||
test_actuators_asctecv1.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
|
test_actuators_asctecv1.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c
|
||||||
test_actuators_asctecv1.CFLAGS += -DUSE_I2C1
|
test_actuators_asctecv1.CFLAGS += -DUSE_I2C1
|
||||||
@@ -560,7 +560,7 @@ test_actuators_asctecv1.srcs += mcu_periph/i2c.c $(SRC_ARCH)/mcu_periph/i2c_ar
|
|||||||
#test_manual.srcs += $(COMMON_TELEMETRY_SRCS)
|
#test_manual.srcs += $(COMMON_TELEMETRY_SRCS)
|
||||||
#
|
#
|
||||||
#test_manual.srcs += test/test_manual.c
|
#test_manual.srcs += test/test_manual.c
|
||||||
#test_manual.srcs += $(SRC_FIRMWARE)/commands.c
|
#test_manual.srcs += subsystems/commands.c
|
||||||
##test_manual.srcs += subsystems/actuators/actuators_pwm.c
|
##test_manual.srcs += subsystems/actuators/actuators_pwm.c
|
||||||
#test_manual.srcs += $(SRC_ARCH)/subsystems/actuators/actuators_pwm_arch.c
|
#test_manual.srcs += $(SRC_ARCH)/subsystems/actuators/actuators_pwm_arch.c
|
||||||
#
|
#
|
||||||
|
|||||||
@@ -104,7 +104,7 @@ ifeq ($(TARGET), ap)
|
|||||||
include $(CFG_SHARED)/i2c_select.makefile
|
include $(CFG_SHARED)/i2c_select.makefile
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ap.srcs += $(SRC_FIRMWARE)/commands.c
|
ap.srcs += subsystems/commands.c
|
||||||
ap.srcs += subsystems/actuators.c
|
ap.srcs += subsystems/actuators.c
|
||||||
|
|
||||||
#
|
#
|
||||||
|
|||||||
@@ -152,7 +152,7 @@ endif
|
|||||||
fbw_CFLAGS += -DFBW
|
fbw_CFLAGS += -DFBW
|
||||||
fbw_srcs += $(SRC_FIRMWARE)/main_fbw.c
|
fbw_srcs += $(SRC_FIRMWARE)/main_fbw.c
|
||||||
fbw_srcs += subsystems/electrical.c
|
fbw_srcs += subsystems/electrical.c
|
||||||
fbw_srcs += $(SRC_FIXEDWING)/commands.c
|
fbw_srcs += subsystems/commands.c
|
||||||
fbw_srcs += subsystems/actuators.c
|
fbw_srcs += subsystems/actuators.c
|
||||||
fbw_srcs += $(SRC_FIRMWARE)/fbw_downlink.c
|
fbw_srcs += $(SRC_FIRMWARE)/fbw_downlink.c
|
||||||
|
|
||||||
|
|||||||
@@ -83,7 +83,7 @@ nps.srcs += $(SRC_FIRMWARE)/telemetry.c \
|
|||||||
$(SRC_ARCH)/ivy_transport.c
|
$(SRC_ARCH)/ivy_transport.c
|
||||||
|
|
||||||
nps.srcs += subsystems/actuators.c
|
nps.srcs += subsystems/actuators.c
|
||||||
nps.srcs += $(SRC_FIRMWARE)/commands.c
|
nps.srcs += subsystems/commands.c
|
||||||
|
|
||||||
nps.srcs += $(SRC_FIRMWARE)/datalink.c
|
nps.srcs += $(SRC_FIRMWARE)/datalink.c
|
||||||
|
|
||||||
|
|||||||
@@ -40,7 +40,7 @@
|
|||||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||||
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
||||||
#include "subsystems/sensors/infrared.h"
|
#include "subsystems/sensors/infrared.h"
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "firmwares/fixedwing/main_ap.h"
|
#include "firmwares/fixedwing/main_ap.h"
|
||||||
#include "ap_downlink.h"
|
#include "ap_downlink.h"
|
||||||
#include "sim_uart.h"
|
#include "sim_uart.h"
|
||||||
|
|||||||
@@ -18,7 +18,7 @@
|
|||||||
#include "subsystems/nav.h"
|
#include "subsystems/nav.h"
|
||||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||||
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
#include "firmwares/fixedwing/guidance/guidance_v.h"
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "firmwares/fixedwing/main_ap.h"
|
#include "firmwares/fixedwing/main_ap.h"
|
||||||
#include "ap_downlink.h"
|
#include "ap_downlink.h"
|
||||||
#include "sim_uart.h"
|
#include "sim_uart.h"
|
||||||
|
|||||||
@@ -28,7 +28,7 @@
|
|||||||
#include "mcu_periph/can.h"
|
#include "mcu_periph/can.h"
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#include "subsystems/datalink/downlink.h"
|
#include "subsystems/datalink/downlink.h"
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "firmwares/rotorcraft/actuators.h"
|
#include "firmwares/rotorcraft/actuators.h"
|
||||||
//#include "booz/booz_radio_control.h"
|
//#include "booz/booz_radio_control.h"
|
||||||
#include "subsystems/imu.h"
|
#include "subsystems/imu.h"
|
||||||
|
|||||||
@@ -33,6 +33,7 @@
|
|||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "std.h"
|
#include "std.h"
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
|
#include "generated/airframe.h"
|
||||||
|
|
||||||
#define THRESHOLD_MANUAL_PPRZ (MIN_PPRZ / 2)
|
#define THRESHOLD_MANUAL_PPRZ (MIN_PPRZ / 2)
|
||||||
|
|
||||||
@@ -57,6 +58,10 @@ extern bool_t kill_throttle;
|
|||||||
/** flight time in seconds. */
|
/** flight time in seconds. */
|
||||||
extern uint16_t autopilot_flight_time;
|
extern uint16_t autopilot_flight_time;
|
||||||
|
|
||||||
|
#define autopilot_ResetFlightTimeAndLaunch(_) { \
|
||||||
|
autopilot_flight_time = 0; launch = FALSE; \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// FIXME, move to control
|
// FIXME, move to control
|
||||||
#define LATERAL_MODE_MANUAL 0
|
#define LATERAL_MODE_MANUAL 0
|
||||||
@@ -85,6 +90,22 @@ extern bool_t gps_lost;
|
|||||||
(_mode != new_mode ? _mode = new_mode, TRUE : FALSE); \
|
(_mode != new_mode ? _mode = new_mode, TRUE : FALSE); \
|
||||||
})
|
})
|
||||||
|
|
||||||
|
/** Commands trim for roll and pitch/
|
||||||
|
*/
|
||||||
|
#ifndef COMMAND_ROLL_TRIM
|
||||||
|
#define COMMAND_ROLL_TRIM 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef COMMAND_PITCH_TRIM
|
||||||
|
#define COMMAND_PITCH_TRIM 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
extern pprz_t command_roll_trim = COMMAND_ROLL_TRIM;
|
||||||
|
extern pprz_t command_pitch_trim = COMMAND_PITCH_TRIM;
|
||||||
|
|
||||||
|
|
||||||
|
/** Power switch control.
|
||||||
|
*/
|
||||||
extern bool_t power_switch;
|
extern bool_t power_switch;
|
||||||
|
|
||||||
#ifdef POWER_SWITCH_LED
|
#ifdef POWER_SWITCH_LED
|
||||||
@@ -96,9 +117,6 @@ extern bool_t power_switch;
|
|||||||
#define autopilot_SetPowerSwitch(_x) { power_switch = _x; }
|
#define autopilot_SetPowerSwitch(_x) { power_switch = _x; }
|
||||||
#endif // POWER_SWITCH_LED
|
#endif // POWER_SWITCH_LED
|
||||||
|
|
||||||
#define autopilot_ResetFlightTimeAndLaunch(_) { \
|
|
||||||
autopilot_flight_time = 0; launch = FALSE; \
|
|
||||||
}
|
|
||||||
|
|
||||||
/* CONTROL_RATE will be removed in the next release
|
/* CONTROL_RATE will be removed in the next release
|
||||||
* please use CONTROL_FREQUENCY instead
|
* please use CONTROL_FREQUENCY instead
|
||||||
|
|||||||
@@ -39,7 +39,7 @@
|
|||||||
#include "messages.h"
|
#include "messages.h"
|
||||||
#include "generated/periodic_telemetry.h"
|
#include "generated/periodic_telemetry.h"
|
||||||
#include "generated/airframe.h"
|
#include "generated/airframe.h"
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
|
|
||||||
#include "mcu_periph/uart.h"
|
#include "mcu_periph/uart.h"
|
||||||
|
|||||||
@@ -36,7 +36,7 @@
|
|||||||
#include "firmwares/fixedwing/main_fbw.h"
|
#include "firmwares/fixedwing/main_fbw.h"
|
||||||
#include "mcu.h"
|
#include "mcu.h"
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
#include "subsystems/electrical.h"
|
#include "subsystems/electrical.h"
|
||||||
#include "subsystems/radio_control.h"
|
#include "subsystems/radio_control.h"
|
||||||
|
|||||||
@@ -23,7 +23,7 @@
|
|||||||
|
|
||||||
#include "subsystems/radio_control.h"
|
#include "subsystems/radio_control.h"
|
||||||
#include "subsystems/gps.h"
|
#include "subsystems/gps.h"
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "firmwares/rotorcraft/navigation.h"
|
#include "firmwares/rotorcraft/navigation.h"
|
||||||
#include "firmwares/rotorcraft/guidance.h"
|
#include "firmwares/rotorcraft/guidance.h"
|
||||||
#include "firmwares/rotorcraft/stabilization.h"
|
#include "firmwares/rotorcraft/stabilization.h"
|
||||||
@@ -102,15 +102,14 @@ void autopilot_periodic(void) {
|
|||||||
#else
|
#else
|
||||||
if (autopilot_mode == AP_MODE_KILL) {
|
if (autopilot_mode == AP_MODE_KILL) {
|
||||||
#endif
|
#endif
|
||||||
SetCommands(commands_failsafe,
|
SetCommands(commands_failsafe);
|
||||||
autopilot_in_flight, autopilot_motors_on);
|
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
guidance_v_run( autopilot_in_flight );
|
guidance_v_run( autopilot_in_flight );
|
||||||
guidance_h_run( autopilot_in_flight );
|
guidance_h_run( autopilot_in_flight );
|
||||||
SetCommands(stabilization_cmd,
|
SetCommands(stabilization_cmd);
|
||||||
autopilot_in_flight, autopilot_motors_on);
|
|
||||||
}
|
}
|
||||||
|
RotorcraftCommandsTest(commands, autopilot_in_flight, autopilot_motors_on);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -65,8 +65,8 @@ extern bool_t autopilot_detect_ground_once;
|
|||||||
|
|
||||||
extern uint16_t autopilot_flight_time;
|
extern uint16_t autopilot_flight_time;
|
||||||
|
|
||||||
|
/** Default RC mode.
|
||||||
|
*/
|
||||||
#ifndef MODE_MANUAL
|
#ifndef MODE_MANUAL
|
||||||
#define MODE_MANUAL AP_MODE_RATE_DIRECT
|
#define MODE_MANUAL AP_MODE_RATE_DIRECT
|
||||||
#endif
|
#endif
|
||||||
@@ -109,6 +109,23 @@ extern uint16_t autopilot_flight_time;
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/** Thrust and Yaw commands limitation.
|
||||||
|
* Limit thrust and/or yaw depending of the in_flight
|
||||||
|
* and motors_on flag status
|
||||||
|
*/
|
||||||
|
#ifndef ROTORCRAFT_COMMANDS_YAW_ALWAYS_ENABLED
|
||||||
|
#define RotorcraftCommandsTest(_cmd, _in_flight, _motor_on) { \
|
||||||
|
if (!(_in_flight)) { _cmd[COMMAND_YAW] = 0; } \
|
||||||
|
if (!(_motor_on)) { _cmd[COMMAND_THRUST] = 0; } \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define RotorcraftCommandsTest(_cmd, _in_flight, _motor_on) { \
|
||||||
|
if (!(_motor_on)) { _cmd[COMMAND_THRUST] = 0; } \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** Ground detection based on accelerometers.
|
||||||
|
*/
|
||||||
#ifndef THRESHOLD_GROUND_DETECT
|
#ifndef THRESHOLD_GROUND_DETECT
|
||||||
#define THRESHOLD_GROUND_DETECT ACCEL_BFP_OF_REAL(15.)
|
#define THRESHOLD_GROUND_DETECT ACCEL_BFP_OF_REAL(15.)
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -1,26 +0,0 @@
|
|||||||
/* $Id$
|
|
||||||
*
|
|
||||||
* (c) 2009 Antoine Drouin <poinix@gmail.com>
|
|
||||||
*
|
|
||||||
* This file is part of paparazzi.
|
|
||||||
*
|
|
||||||
* paparazzi is free software; you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation; either version 2, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* paparazzi is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with paparazzi; see the file COPYING. If not, write to
|
|
||||||
* the Free Software Foundation, 59 Temple Place - Suite 330,
|
|
||||||
* Boston, MA 02111-1307, USA.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
|
||||||
|
|
||||||
int32_t commands[COMMANDS_NB];
|
|
||||||
const int32_t commands_failsafe[COMMANDS_NB] = COMMANDS_FAILSAFE;
|
|
||||||
@@ -1,49 +0,0 @@
|
|||||||
/* $Id$
|
|
||||||
*
|
|
||||||
* (c) 2009 Antoine Drouin <poinix@gmail.com>
|
|
||||||
*
|
|
||||||
* This file is part of paparazzi.
|
|
||||||
*
|
|
||||||
* paparazzi is free software; you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation; either version 2, or (at your option)
|
|
||||||
* any later version.
|
|
||||||
*
|
|
||||||
* paparazzi is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with paparazzi; see the file COPYING. If not, write to
|
|
||||||
* the Free Software Foundation, 59 Temple Place - Suite 330,
|
|
||||||
* Boston, MA 02111-1307, USA.
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef COMMANDS_H
|
|
||||||
#define COMMANDS_H
|
|
||||||
|
|
||||||
#include "paparazzi.h"
|
|
||||||
#include "generated/airframe.h"
|
|
||||||
|
|
||||||
extern int32_t commands[COMMANDS_NB];
|
|
||||||
extern const int32_t commands_failsafe[COMMANDS_NB];
|
|
||||||
|
|
||||||
#ifndef ROTORCRAFT_COMMANDS_YAW_ALWAYS_ENABLED
|
|
||||||
#define SetCommands(_in_cmd, _in_flight, _motors_on) { \
|
|
||||||
commands[COMMAND_PITCH] = _in_cmd[COMMAND_PITCH]; \
|
|
||||||
commands[COMMAND_ROLL] = _in_cmd[COMMAND_ROLL]; \
|
|
||||||
commands[COMMAND_YAW] = (_in_flight) ? _in_cmd[COMMAND_YAW] : 0; \
|
|
||||||
commands[COMMAND_THRUST] = (_motors_on) ? _in_cmd[COMMAND_THRUST] : 0; \
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
#define SetCommands(_in_cmd, _in_flight, _motors_on) { \
|
|
||||||
commands[COMMAND_PITCH] = _in_cmd[COMMAND_PITCH]; \
|
|
||||||
commands[COMMAND_ROLL] = _in_cmd[COMMAND_ROLL]; \
|
|
||||||
commands[COMMAND_YAW] = _in_cmd[COMMAND_YAW]; \
|
|
||||||
commands[COMMAND_THRUST] = (_motors_on) ? _in_cmd[COMMAND_THRUST] : 0; \
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif /* COMMANDS_H */
|
|
||||||
@@ -35,7 +35,7 @@
|
|||||||
#include "subsystems/settings.h"
|
#include "subsystems/settings.h"
|
||||||
#include "subsystems/datalink/xbee.h"
|
#include "subsystems/datalink/xbee.h"
|
||||||
|
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
#if USE_MOTOR_MIXING
|
#if USE_MOTOR_MIXING
|
||||||
#include "subsystems/actuators/motor_mixing.h"
|
#include "subsystems/actuators/motor_mixing.h"
|
||||||
|
|||||||
@@ -24,7 +24,7 @@
|
|||||||
#include "mcu_periph/uart.h"
|
#include "mcu_periph/uart.h"
|
||||||
#include "led.h"
|
#include "led.h"
|
||||||
|
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
// LINK
|
// LINK
|
||||||
|
|||||||
@@ -26,7 +26,7 @@
|
|||||||
#include "mcu_periph/uart.h"
|
#include "mcu_periph/uart.h"
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#include "subsystems/datalink/downlink.h"
|
#include "subsystems/datalink/downlink.h"
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
#include "subsystems/actuators/actuators_pwm.h"
|
#include "subsystems/actuators/actuators_pwm.h"
|
||||||
#include "subsystems/imu.h"
|
#include "subsystems/imu.h"
|
||||||
|
|||||||
@@ -24,7 +24,7 @@
|
|||||||
|
|
||||||
#include "mcu.h"
|
#include "mcu.h"
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
#include "subsystems/datalink/downlink.h"
|
#include "subsystems/datalink/downlink.h"
|
||||||
#include "led.h"
|
#include "led.h"
|
||||||
|
|||||||
@@ -1,5 +1,4 @@
|
|||||||
/* $Id$
|
/*
|
||||||
*
|
|
||||||
* (c) 2006 Pascal Brisset, Antoine Drouin
|
* (c) 2006 Pascal Brisset, Antoine Drouin
|
||||||
*
|
*
|
||||||
* This file is part of paparazzi.
|
* This file is part of paparazzi.
|
||||||
@@ -26,18 +25,7 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
|
|
||||||
#ifndef COMMAND_ROLL_TRIM
|
|
||||||
#define COMMAND_ROLL_TRIM 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef COMMAND_PITCH_TRIM
|
|
||||||
#define COMMAND_PITCH_TRIM 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
pprz_t command_roll_trim = COMMAND_ROLL_TRIM;
|
|
||||||
pprz_t command_pitch_trim = COMMAND_PITCH_TRIM;
|
|
||||||
|
|
||||||
pprz_t commands[COMMANDS_NB];
|
pprz_t commands[COMMANDS_NB];
|
||||||
const pprz_t commands_failsafe[COMMANDS_NB] = COMMANDS_FAILSAFE;
|
const pprz_t commands_failsafe[COMMANDS_NB] = COMMANDS_FAILSAFE;
|
||||||
@@ -1,5 +1,4 @@
|
|||||||
/* $Id$
|
/*
|
||||||
*
|
|
||||||
* (c) 2006 Pascal Brisset, Antoine Drouin
|
* (c) 2006 Pascal Brisset, Antoine Drouin
|
||||||
*
|
*
|
||||||
* This file is part of paparazzi.
|
* This file is part of paparazzi.
|
||||||
@@ -32,14 +31,12 @@
|
|||||||
#include "paparazzi.h"
|
#include "paparazzi.h"
|
||||||
#include "generated/airframe.h"
|
#include "generated/airframe.h"
|
||||||
|
|
||||||
extern pprz_t command_roll_trim;
|
/** Storage of intermediate command values.
|
||||||
extern pprz_t command_pitch_trim;
|
* These values come from the RC (MANUAL mode), from the autopilot (AUTO mode) or from control loops.
|
||||||
|
* They are asyncronisly used to set the servos
|
||||||
|
*/
|
||||||
extern pprz_t commands[COMMANDS_NB];
|
extern pprz_t commands[COMMANDS_NB];
|
||||||
extern const pprz_t commands_failsafe[COMMANDS_NB];
|
extern const pprz_t commands_failsafe[COMMANDS_NB];
|
||||||
/** Storage of intermediate command values: these values come from
|
|
||||||
the RC (MANUAL mode), from the autopilot (AUTO mode) or from control loops.
|
|
||||||
They are asyncronisly used to set the servos */
|
|
||||||
|
|
||||||
#define SetCommands(t) { \
|
#define SetCommands(t) { \
|
||||||
int i; \
|
int i; \
|
||||||
@@ -1,7 +1,7 @@
|
|||||||
#include "subsystems/electrical.h"
|
#include "subsystems/electrical.h"
|
||||||
|
|
||||||
#include "mcu_periph/adc.h"
|
#include "mcu_periph/adc.h"
|
||||||
#include "commands.h"
|
#include "subsystems/commands.h"
|
||||||
|
|
||||||
#include "generated/airframe.h"
|
#include "generated/airframe.h"
|
||||||
#include BOARD_CONFIG
|
#include BOARD_CONFIG
|
||||||
|
|||||||
@@ -27,7 +27,7 @@
|
|||||||
#include "led.h"
|
#include "led.h"
|
||||||
|
|
||||||
#include "mcu_periph/i2c.h"
|
#include "mcu_periph/i2c.h"
|
||||||
#include "firmwares/rotorcraft/commands.h"
|
#include "subsystems/commands.h"
|
||||||
#include "subsystems/actuators.h"
|
#include "subsystems/actuators.h"
|
||||||
|
|
||||||
static inline void main_init( void );
|
static inline void main_init( void );
|
||||||
|
|||||||
Reference in New Issue
Block a user