mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
[modules] move intermcu to modules
both fixedwing and rotorcraft
This commit is contained in:
@@ -12,7 +12,7 @@
|
||||
<include name="generated/airframe.h"/>
|
||||
<include name="autopilot.h"/>
|
||||
<include name="autopilot_rc_helpers.h"/>
|
||||
<include name="inter_mcu.h"/>
|
||||
<include name="modules/intermcu/inter_mcu.h"/>
|
||||
<include name="nav.h"/>
|
||||
<include name="guidance/guidance_common.h"/>
|
||||
<include name="guidance/guidance_h.h"/>
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
<include name="generated/airframe.h"/>
|
||||
<include name="autopilot.h"/>
|
||||
<include name="autopilot_rc_helpers.h"/>
|
||||
<include name="inter_mcu.h"/>
|
||||
<include name="modules/intermcu/inter_mcu.h"/>
|
||||
<include name="nav.h"/>
|
||||
<include name="guidance/guidance_common.h"/>
|
||||
<include name="guidance/guidance_h.h"/>
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
<define name="AHRS_MAG_CORRECT_FREQUENCY" value="$(AHRS_MAG_CORRECT_FREQUENCY)" cond="ifdef AHRS_MAG_CORRECT_FREQUENCY"/>
|
||||
<include name="$(SRC_FIRMWARE)"/>
|
||||
<define name="INTER_MCU"/>
|
||||
<file name="inter_mcu.c" dir="."/>
|
||||
<file name="inter_mcu.c" dir="modules/intermcu"/>
|
||||
</makefile>
|
||||
<makefile target="ap">
|
||||
<file name="main.c" dir="$(SRC_FIRMWARE)" cond="ifneq ($(RTOS), chibios)"/>
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
</raw>
|
||||
<define name="INTER_MCU"/>
|
||||
<define name="MCU_CAN_LINK"/>
|
||||
<file name="link_mcu_can.c" dir="."/>
|
||||
<file name="link_mcu_can.c"/>
|
||||
<file name="can.c" dir="mcu_periph"/>
|
||||
<file name="can_arch.c" dir="$(SRC_ARCH)/mcu_periph"/>
|
||||
</makefile>
|
||||
|
||||
@@ -26,7 +26,7 @@
|
||||
<configure name="INTER_MCU_SPI" default="SPI1"/>
|
||||
<configure name="INTER_MCU_SLAVE" default="SLAVE0"/>
|
||||
<define name="MCU_SPI_LINK"/>
|
||||
<file name="link_mcu_spi.c" dir="."/>
|
||||
<file name="link_mcu_spi.c"/>
|
||||
<file name="spi.c" dir="mcu_periph"/>
|
||||
<file name="spi_arch.c" dir="$(SRC_ARCH)/mcu_periph"/>
|
||||
</makefile>
|
||||
|
||||
@@ -19,8 +19,8 @@
|
||||
<provides>intermcu,commands,radio_control</provides>
|
||||
</dep>
|
||||
<header>
|
||||
<file name="intermcu.h" dir="subsystems" cond="ROTORCRAFT_FIRMWARE"/>
|
||||
<file name="inter_mcu.h" dir="." cond="FIXEDWING_FIRMWARE"/>
|
||||
<file name="intermcu.h" cond="ROTORCRAFT_FIRMWARE"/>
|
||||
<file name="inter_mcu.h" cond="FIXEDWING_FIRMWARE"/>
|
||||
</header>
|
||||
<init fun="intermcu_init()"/>
|
||||
<periodic fun="intermcu_periodic()"/>
|
||||
@@ -46,7 +46,7 @@
|
||||
<define name="INTERMCU_LINK" value="$(INTERMCU_PORT_LOWER)"/>
|
||||
<define name="USE_$(INTERMCU_PORT_UPPER)"/>
|
||||
<define name="$(INTERMCU_PORT_UPPER)_BAUD" value="$(INTERMCU_BAUD)"/>
|
||||
<file name="link_mcu_usart.c" dir="."/>
|
||||
<file name="link_mcu_usart.c"/>
|
||||
</makefile>
|
||||
|
||||
<makefile target="fbw" firmware="rotorcraft">
|
||||
@@ -55,19 +55,19 @@
|
||||
<define name="FBW_MODE_LED" value="$(FBW_MODE_LED)" cond="ifneq ($(FBW_MODE_LED),none)"/>
|
||||
<define name="INTER_MCU_FBW"/>
|
||||
<define name="DOWNLINK"/>
|
||||
<file name="intermcu_fbw.c" dir="subsystems/intermcu"/>
|
||||
<file name="intermcu_fbw.c"/>
|
||||
</makefile>
|
||||
<makefile target="ap" firmware="rotorcraft">
|
||||
<configure name="INTERMCU_PORT" default="UART3" case="upper|lower"/>
|
||||
<configure name="RADIO_CONTROL_LED" value="none"/>
|
||||
<define name="INTER_MCU_AP"/>
|
||||
<define name="RADIO_CONTROL_TYPE_H" value="subsystems/intermcu/intermcu_ap.h" type="string"/>
|
||||
<define name="RADIO_CONTROL_TYPE_H" value="modules/intermcu/intermcu_ap.h" type="string"/>
|
||||
<define name="RADIO_CONTROL"/>
|
||||
<define name="RADIO_CONTROL_LED" value="$(RADIO_CONTROL_LED)" cond="ifneq ($(RADIO_CONTROL_LED),none)"/>
|
||||
<define name="GPS_SECONDARY_TYPE_H" value="subsystems/intermcu/intermcu_ap.h" type="string" cond="ifneq (,$(findstring $(SECONDARY_GPS), imcu))"/>
|
||||
<define name="GPS_SECONDARY_TYPE_H" value="modules/intermcu/intermcu_ap.h" type="string" cond="ifneq (,$(findstring $(SECONDARY_GPS), imcu))"/>
|
||||
<define name="SECONDARY_GPS" value="GPS_IMCU" cond="ifneq (,$(findstring $(SECONDARY_GPS), imcu))"/>
|
||||
<define name="IMCU_GPS" cond="ifneq (,$(findstring $(SECONDARY_GPS), imcu))"/>
|
||||
<file name="intermcu_ap.c" dir="subsystems/intermcu"/>
|
||||
<file name="intermcu_ap.c"/>
|
||||
<file name="radio_control.c" dir="modules/radio_control"/>
|
||||
</makefile>
|
||||
<makefile target="ap|fbw" firmware="rotorcraft">
|
||||
|
||||
@@ -33,7 +33,7 @@
|
||||
<dl_settings>
|
||||
<dl_settings NAME="control horiz">
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
<dl_setting MAX="9000" MIN="-9000" STEP="1" VAR="ap_state->command_yaw_trim" shortname="yaw_trim" param="COMMAND_YAW_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
@@ -23,7 +23,7 @@
|
||||
<dl_settings>
|
||||
<dl_settings NAME="control horiz">
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
<dl_setting MAX="9000" MIN="-9000" STEP="1" VAR="ap_state->command_yaw_trim" shortname="yaw_trim" param="COMMAND_YAW_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
<dl_settings NAME="control">
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
<dl_settings NAME="control">
|
||||
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
<dl_setting MAX="9000" MIN="-9000" STEP="1" VAR="ap_state->command_yaw_trim" shortname="yaw_trim" param="COMMAND_YAW_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
<dl_settings NAME="control">
|
||||
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
<dl_settings NAME="control">
|
||||
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
<dl_settings NAME="control">
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
<dl_settings NAME="control">
|
||||
<dl_settings NAME="trim">
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_roll_trim" shortname="roll_trim" module="modules/intermcu/inter_mcu" param="COMMAND_ROLL_TRIM"/>
|
||||
<dl_setting MAX="960" MIN="-960" STEP="1" VAR="ap_state->command_pitch_trim" shortname="pitch_trim" param="COMMAND_PITCH_TRIM"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include <time.h>
|
||||
#include <string.h>
|
||||
#include "std.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "autopilot.h"
|
||||
#include "modules/gps/gps.h"
|
||||
#include "generated/settings.h"
|
||||
|
||||
@@ -29,8 +29,8 @@
|
||||
#include "autopilot.h"
|
||||
#include "firmwares/fixedwing/autopilot_static.h"
|
||||
|
||||
#include "inter_mcu.h"
|
||||
#include "link_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "modules/intermcu/link_mcu.h"
|
||||
#include "state.h"
|
||||
#include "firmwares/fixedwing/nav.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
#define AUTOPILOT_UTILS_H
|
||||
|
||||
#include "std.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
/** Get mode from pulse
|
||||
|
||||
@@ -37,8 +37,8 @@
|
||||
#include "firmwares/fixedwing/main_ap.h"
|
||||
#include "mcu.h"
|
||||
#include "mcu_periph/sys_time.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "link_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "modules/intermcu/link_mcu.h"
|
||||
|
||||
#include "generated/airframe.h"
|
||||
#include "generated/modules.h"
|
||||
|
||||
@@ -57,8 +57,8 @@
|
||||
#include "firmwares/fixedwing/fbw_datalink.h"
|
||||
#endif
|
||||
|
||||
#include "inter_mcu.h"
|
||||
#include "link_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "modules/intermcu/link_mcu.h"
|
||||
|
||||
uint8_t fbw_mode;
|
||||
|
||||
|
||||
@@ -34,7 +34,7 @@ static unit_t unit __attribute__((unused));
|
||||
#include "firmwares/fixedwing/nav.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
#include "autopilot.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "modules/gps/gps.h"
|
||||
|
||||
#include "generated/flight_plan.h"
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "modules/radio_control/radio_control.h"
|
||||
#include "subsystems/intermcu/intermcu_fbw.h"
|
||||
#include "modules/intermcu/intermcu_fbw.h"
|
||||
#include "firmwares/rotorcraft/main_fbw.h"
|
||||
#include "firmwares/rotorcraft/autopilot_rc_helpers.h"
|
||||
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
|
||||
#include <math.h>
|
||||
#include <inttypes.h>
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "modules/nav/common_nav.h"
|
||||
#include "autopilot.h"
|
||||
#include "generated/flight_plan.h"
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
*/
|
||||
|
||||
#include "modules/boards/opa_controller_ap.h"
|
||||
#include "subsystems/intermcu.h"
|
||||
#include "modules/intermcu/intermcu.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
*/
|
||||
|
||||
#include "modules/boards/opa_controller_fbw.h"
|
||||
#include "subsystems/intermcu.h"
|
||||
#include "modules/intermcu/intermcu.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
#include "led.h"
|
||||
|
||||
@@ -28,7 +28,7 @@
|
||||
#define CAM_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
#define CAM_MODE_OFF 0 /* Do nothing */
|
||||
#define CAM_MODE_ANGLES 1 /* Input: servo angles */
|
||||
|
||||
@@ -31,7 +31,7 @@
|
||||
#include "autopilot.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "state.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
#ifndef CAM_PHI_MAX
|
||||
#define CAM_PHI_MAX RadOfDeg(45)
|
||||
|
||||
@@ -31,7 +31,7 @@
|
||||
#include "modules/gps/gps.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "autopilot.h"
|
||||
#include "modules/nav/common_nav.h"
|
||||
|
||||
|
||||
@@ -27,7 +27,7 @@
|
||||
#include "modules/core/rc_settings.h"
|
||||
#include "autopilot.h"
|
||||
#include "firmwares/fixedwing/nav.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
|
||||
|
||||
uint8_t rc_settings_mode = 0;
|
||||
|
||||
@@ -27,7 +27,7 @@
|
||||
*/
|
||||
|
||||
#include "dc_shoot_rc.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "dc.h"
|
||||
|
||||
#ifndef DC_RADIO_SHOOT
|
||||
|
||||
@@ -33,7 +33,7 @@
|
||||
|
||||
// Include Servo and airframe servo channels
|
||||
#include "std.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "generated/airframe.h"
|
||||
|
||||
#define DC_PUSH(X) imcu_set_command(X, -MAX_PPRZ);
|
||||
|
||||
@@ -28,7 +28,7 @@
|
||||
#include "std.h"
|
||||
//#include "stdio.h"
|
||||
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
#include "mcu_periph/sys_time.h"
|
||||
#include "mcu_periph/gpio.h"
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
int gas_engine_idle_trim_left = 0;
|
||||
int gas_engine_idle_trim_right = 0;
|
||||
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
|
||||
void periodic_gas_engine_idle_trim(void)
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
|
||||
// Command vector for thrust
|
||||
#include "generated/airframe.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
#define NB_DATA 9
|
||||
|
||||
|
||||
@@ -19,12 +19,12 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file inter_mcu.c
|
||||
* @file modules/intermcu/inter_mcu.c
|
||||
* Communication between fbw and ap processes.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
#if defined SINGLE_MCU
|
||||
static struct fbw_state _fbw_state;
|
||||
@@ -32,7 +32,7 @@ static struct ap_state _ap_state;
|
||||
struct fbw_state *fbw_state = &_fbw_state;
|
||||
struct ap_state *ap_state = &_ap_state;
|
||||
#else /* SINGLE_MCU */
|
||||
#include "link_mcu.h"
|
||||
#include "modules/intermcu/link_mcu.h"
|
||||
struct fbw_state *fbw_state = &link_mcu_from_fbw_msg.payload.from_fbw;
|
||||
struct ap_state *ap_state = &link_mcu_from_ap_msg.payload.from_ap;
|
||||
#endif /* ! SINGLE_MCU */
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file inter_mcu.h
|
||||
* @file modules/intermcu/inter_mcu.h
|
||||
* Communication between fbw and ap processes.
|
||||
*
|
||||
* This unit contains the data structure used to communicate between the
|
||||
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file subsystems/intermcu.h
|
||||
/** @file modules/intermcu/intermcu.h
|
||||
* @brief Rotorcraft Inter-MCU interface
|
||||
*/
|
||||
|
||||
+1
-1
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file subsystems/intermcu/intermcu_ap.c
|
||||
/** @file modules/intermcu/intermcu_ap.c
|
||||
* @brief Rotorcraft Inter-MCU on the autopilot
|
||||
*/
|
||||
|
||||
+2
-2
@@ -20,14 +20,14 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file subsystems/intermcu/intermcu_ap.h
|
||||
/** @file modules/intermcu/intermcu_ap.h
|
||||
* @brief Rotorcraft Inter-MCU on the autopilot
|
||||
*/
|
||||
|
||||
#ifndef INTERMCU_AP_ROTORCRAFT_H
|
||||
#define INTERMCU_AP_ROTORCRAFT_H
|
||||
|
||||
#include "subsystems/intermcu.h"
|
||||
#include "modules/intermcu/intermcu.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "modules/energy/electrical.h"
|
||||
|
||||
+1
-1
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file subsystems/intermcu/intermcu_fbw.c
|
||||
/** @file modules/intermcu/intermcu_fbw.c
|
||||
* @brief Rotorcraft Inter-MCU on FlyByWire
|
||||
*/
|
||||
|
||||
+2
-2
@@ -20,14 +20,14 @@
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file subsystems/intermcu/intermcu_fbw.h
|
||||
/** @file modules/intermcu/intermcu_fbw.h
|
||||
* @brief Rotorcraft Inter-MCU on FlyByWire
|
||||
*/
|
||||
|
||||
#ifndef INTERMCU_FBW_ROTORCRAFT_H
|
||||
#define INTERMCU_FBW_ROTORCRAFT_H
|
||||
|
||||
#include "subsystems/intermcu.h"
|
||||
#include "modules/intermcu/intermcu.h"
|
||||
|
||||
extern bool autopilot_motors_on;
|
||||
extern pprz_t intermcu_commands[COMMANDS_NB];
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file link_mcu.h
|
||||
* @file modules/intermcu/link_mcu.h
|
||||
* Common transport functions for the communication between FBW and AP.
|
||||
*/
|
||||
|
||||
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include "link_mcu_can.h"
|
||||
#include "modules/intermcu/link_mcu_can.h"
|
||||
#include "mcu_periph/can.h"
|
||||
#include "led.h"
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file link_mcu_can.h
|
||||
* @file modules/intermcu/link_mcu_can.h
|
||||
* Transport for the communication between FBW and AP via CAN.
|
||||
*
|
||||
*/
|
||||
@@ -28,7 +28,7 @@
|
||||
#define LINK_MCU_CAN_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
struct link_mcu_msg {
|
||||
union {
|
||||
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include "link_mcu_spi.h"
|
||||
#include "modules/intermcu/link_mcu_spi.h"
|
||||
|
||||
#ifndef LINK_MCU_SPI_DEV
|
||||
#define LINK_MCU_SPI_DEV spi1
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file link_mcu_spi.h
|
||||
* @file modules/intermcu/link_mcu_spi.h
|
||||
* Transport for the communication between FBW and AP via SPI.
|
||||
*
|
||||
*/
|
||||
@@ -28,11 +28,11 @@
|
||||
#define LINK_MCU_SPI_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
#include "mcu_periph/spi.h"
|
||||
|
||||
#ifndef SITL
|
||||
#include "link_mcu_hw.h"
|
||||
#include "modules/intermcu/link_mcu_hw.h"
|
||||
#endif
|
||||
|
||||
struct link_mcu_msg {
|
||||
@@ -20,7 +20,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include "link_mcu_usart.h"
|
||||
#include "modules/intermcu/link_mcu_usart.h"
|
||||
#include "mcu_periph/uart.h"
|
||||
#include "led.h"
|
||||
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file link_mcu_usart.h
|
||||
* @file modules/intermcu/link_mcu_usart.h
|
||||
* Transport for the communication between FBW and AP via UART.
|
||||
*
|
||||
*/
|
||||
@@ -28,7 +28,7 @@
|
||||
#define LINK_MCU_USART_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
struct link_mcu_msg {
|
||||
union {
|
||||
@@ -30,7 +30,7 @@
|
||||
#include "state.h"
|
||||
#include "generated/flight_plan.h"
|
||||
#include "generated/airframe.h"
|
||||
#include "inter_mcu.h"
|
||||
#include "modules/intermcu/inter_mcu.h"
|
||||
|
||||
|
||||
#if defined WP_RELEASE
|
||||
|
||||
@@ -27,7 +27,7 @@
|
||||
#include "modules/px4_flash/px4_flash.h"
|
||||
#include "modules/px4_flash/protocol.h"
|
||||
#include "mcu_periph/sys_time_arch.h"
|
||||
#include "subsystems/intermcu/intermcu_ap.h"
|
||||
#include "modules/intermcu/intermcu_ap.h"
|
||||
|
||||
// Serial Port
|
||||
#include "mcu_periph/uart.h"
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user