Skip to content

Commit

Permalink
[mavlink] Basic implementation (needs cleanup)
Browse files Browse the repository at this point in the history
  • Loading branch information
fvantienen authored and flixr committed Dec 8, 2014
1 parent bcffffa commit 6a77b96
Show file tree
Hide file tree
Showing 135 changed files with 46,852 additions and 8 deletions.
3 changes: 2 additions & 1 deletion conf/firmwares/rotorcraft.makefile
Expand Up @@ -28,10 +28,11 @@ SRC_BOARD=boards/$(BOARD)
SRC_FIRMWARE=firmwares/rotorcraft
SRC_SUBSYSTEMS=subsystems
SRC_MODULES=modules
SRC_EXT=$(PAPARAZZI_SRC)/sw/ext

SRC_ARCH=arch/$(ARCH)

ROTORCRAFT_INC = -I$(SRC_FIRMWARE) -I$(SRC_BOARD)
ROTORCRAFT_INC = -I$(SRC_FIRMWARE) -I$(SRC_BOARD) -I$(SRC_EXT)


ap.ARCHDIR = $(ARCH)
Expand Down
18 changes: 18 additions & 0 deletions conf/modules/mavlink.xml
@@ -0,0 +1,18 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="datalink">
<doc>
<description>Basic MAVLink implementation</description>
</doc>
<header>
<file name="mavlink.h"/>
</header>

<init fun="mavlink_init()"/>
<periodic fun="mavlink_periodic()" autorun="TRUE"/>
<event fun="mavlink_event()"/>

<makefile>
<file name="mavlink.c"/>
</makefile>
</module>
2 changes: 2 additions & 0 deletions sw/airborne/firmwares/fixedwing/autopilot.c
Expand Up @@ -152,6 +152,7 @@ void autopilot_init(void) {
gpio_clear(POWER_SWITCH_GPIO);
#endif

#if PERIODIC_TELEMETRY
/* register some periodic message */
register_periodic_telemetry(DefaultPeriodic, "ALIVE", send_alive);
register_periodic_telemetry(DefaultPeriodic, "PPRZ_MODE", send_mode);
Expand All @@ -165,5 +166,6 @@ void autopilot_init(void) {
#if defined RADIO_CALIB && defined RADIO_CONTROL_SETTINGS
register_periodic_telemetry(DefaultPeriodic, "RC_SETTINGS", send_rc_settings);
#endif
#endif
}

4 changes: 3 additions & 1 deletion sw/airborne/firmwares/fixedwing/main_ap.c
Expand Up @@ -199,7 +199,7 @@ void init_ap( void ) {
ahrs_init();
#endif

#if USE_AHRS && USE_IMU
#if USE_AHRS && USE_IMU && PERIODIC_TELEMETRY
register_periodic_telemetry(DefaultPeriodic, "STATE_FILTER_STATUS", send_filter_status);
#endif

Expand Down Expand Up @@ -449,7 +449,9 @@ void reporting_task( void ) {
/** then report periodicly */
else {
//PeriodicSendAp(DefaultChannel, DefaultDevice);
#if PERIODIC_TELEMETRY
periodic_telemetry_send_Ap(&(DefaultChannel).trans_tx, &(DefaultDevice).device);
#endif
}
}

Expand Down
5 changes: 4 additions & 1 deletion sw/airborne/firmwares/rotorcraft/autopilot.c
Expand Up @@ -138,6 +138,7 @@ PRINT_CONFIG_MSG("Enabled UNLOCKED_HOME_MODE since MODE_AUTO2 is AP_MODE_HOME")
#endif
#endif

#if PERIODIC_TELEMETRY
static void send_alive(struct transport_tx *trans, struct link_device *dev) {
pprz_msg_send_ALIVE(trans, dev, AC_ID, 16, MD5SUM);
}
Expand Down Expand Up @@ -235,7 +236,7 @@ static void send_rotorcraft_cmd(struct transport_tx *trans, struct link_device *
&stabilization_cmd[COMMAND_YAW],
&stabilization_cmd[COMMAND_THRUST]);
}

#endif // PERIODIC_TELEMTRY

void autopilot_init(void) {
/* mode is finally set at end of init if MODE_STARTUP is not KILL */
Expand Down Expand Up @@ -269,6 +270,7 @@ void autopilot_init(void) {
/* set startup mode, propagates through to guidance h/v */
autopilot_set_mode(MODE_STARTUP);

#if PERIODIC_TELEMETRY
register_periodic_telemetry(DefaultPeriodic, "ALIVE", send_alive);
register_periodic_telemetry(DefaultPeriodic, "ROTORCRAFT_STATUS", send_status);
register_periodic_telemetry(DefaultPeriodic, "ENERGY", send_energy);
Expand All @@ -282,6 +284,7 @@ void autopilot_init(void) {
register_periodic_telemetry(DefaultPeriodic, "RC", send_rc);
register_periodic_telemetry(DefaultPeriodic, "ROTORCRAFT_RADIO_CONTROL", send_rotorcraft_rc);
#endif
#endif
}


Expand Down
15 changes: 14 additions & 1 deletion sw/airborne/firmwares/rotorcraft/main.c
Expand Up @@ -124,7 +124,9 @@ tid_t modules_tid; ///< id for modules_periodic_task() timer
tid_t failsafe_tid; ///< id for failsafe_check() timer
tid_t radio_control_tid; ///< id for radio_control_periodic_task() timer
tid_t electrical_tid; ///< id for electrical_periodic() timer
#if PERIODIC_TELEMETRY
tid_t telemetry_tid; ///< id for telemetry_periodic() timer
#endif
#if USE_BARO_BOARD
tid_t baro_tid; ///< id for baro_periodic() timer
#endif
Expand Down Expand Up @@ -184,7 +186,9 @@ STATIC_INLINE void main_init( void ) {
radio_control_tid = sys_time_register_timer((1./60.), NULL);
failsafe_tid = sys_time_register_timer(0.05, NULL);
electrical_tid = sys_time_register_timer(0.1, NULL);
#if PERIODIC_TELEMETRY
telemetry_tid = sys_time_register_timer((1./TELEMETRY_FREQUENCY), NULL);
#endif
#if USE_BARO_BOARD
baro_tid = sys_time_register_timer(1./BARO_PERIODIC_FREQUENCY, NULL);
#endif
Expand All @@ -201,8 +205,10 @@ STATIC_INLINE void handle_periodic_tasks( void ) {
failsafe_check();
if (sys_time_check_and_ack_timer(electrical_tid))
electrical_periodic();
#if PERIODIC_TELEMETRY
if (sys_time_check_and_ack_timer(telemetry_tid))
telemetry_periodic();
#endif
#if USE_BARO_BOARD
if (sys_time_check_and_ack_timer(baro_tid))
baro_periodic();
Expand All @@ -220,15 +226,22 @@ STATIC_INLINE void main_periodic( void ) {
SetActuatorsFromCommands(commands, autopilot_mode);

if (autopilot_in_flight) {
RunOnceEvery(PERIODIC_FREQUENCY, { autopilot_flight_time++; datalink_time++; });
RunOnceEvery(PERIODIC_FREQUENCY, {
autopilot_flight_time++;
#if PERIODIC_TELEMETRY
datalink_time++;
#endif
});
}

RunOnceEvery(10, LED_PERIODIC());
}

#if PERIODIC_TELEMETRY
STATIC_INLINE void telemetry_periodic(void) {
periodic_telemetry_send_Main(&(DefaultChannel).trans_tx, &(DefaultDevice).device);
}
#endif

/** mode to enter when RC is lost while using a mode with RC input (not AP_MODE_NAV) */
#ifndef RC_LOST_MODE
Expand Down
2 changes: 2 additions & 0 deletions sw/airborne/firmwares/rotorcraft/main.h
Expand Up @@ -39,7 +39,9 @@ STATIC_INLINE void main_event( void );
STATIC_INLINE void handle_periodic_tasks( void );

STATIC_INLINE void main_periodic( void );
#if PERIODIC_TELEMETRY
STATIC_INLINE void telemetry_periodic(void);
#endif
STATIC_INLINE void failsafe_check( void );


Expand Down

0 comments on commit 6a77b96

Please sign in to comment.