void event_task_ap( void ) {

  /***** Datalink *******/
  if (PprzBuffer()) {
    ReadPprzBuffer();
    if (pprz_msg_received) {
      pprz_parse_payload();
      pprz_msg_received = FALSE;

      if (dl_msg_available) {
	dl_parse_msg();
	dl_msg_available = FALSE;
      }
    }
  }

  /* parse and use GPS messages */
  if (GpsBuffer()) {
    ReadGpsBuffer();
  }
  if (gps_msg_received) {
    parse_gps_msg();
    gps_msg_received = FALSE;
    if (gps_pos_available) {
      use_gps_pos();
      gps_pos_available = FALSE;
    }
  }

  
}
Exemple #2
0
value set_datalink_message(value s) {
  int n = string_length(s);
  char *ss = String_val(s);
  assert(n <= MSG_SIZE);

  int i;
  for(i = 0; i < n; i++)
    dl_buffer[i] = ss[i];

  dl_parse_msg();
  return Val_unit;
}
Exemple #3
0
/********** EVENT ************************************************************/
void event_task_rctx( void) {
#ifdef RADIO_CONTROL
  if (ppm_valid) {
    ppm_valid = FALSE;
    radio_control_event_task();

#ifdef USE_RCTX_MODE_SWITCH
    // TODO: set rxtx_mode from GPIO connected switch (e.g. I2C pins)
#else
    rctx_mode = PPRZ_MODE_OF_PULSE(rc_values[RADIO_MODE], 0) & 3;
#endif

    rctx_mode |= rctx_under_voltage << 2;
LED_TOGGLE(3);

    if (1)
    // TODO: check XBee busy pin
    // TODO: send only if aircraft is listening
    // TODO: send (here) only in auto1 and manual
    {
      DOWNLINK_SEND_RC_3CH(
            &rctx_mode,
            &rc_values[RADIO_THROTTLE],
            &rc_values[RADIO_ROLL],
            &rc_values[RADIO_PITCH]);
    }
  }
#endif

#if defined DATALINK

#if DATALINK == XBEE
  if (XBeeBuffer()) {
    ReadXBeeBuffer();
    if (xbee_msg_received) {
      xbee_parse_payload();
      xbee_msg_received = FALSE;
    }
  }
#endif

  if (dl_msg_available) {
    dl_parse_msg();
    dl_msg_available = FALSE;
  }
#endif /* DATALINK */
}
Exemple #4
0
/*********** EVENT ***********************************************************/
void event_task_ap( void ) {

#ifdef USE_ANALOG_IMU
  ImuEvent(on_gyro_accel_event, on_mag_event);
#endif // USE_ANALOG_IMU

#ifdef USE_GPS
#if !(defined HITL) && !(defined UBX_EXTERNAL) /** else comes through the datalink */
  if (GpsBuffer()) {
    ReadGpsBuffer();
  }
#endif
  if (gps_msg_received) {
    /* parse and use GPS messages */
#ifdef GPS_CONFIGURE
    if (gps_configuring)
      gps_configure();
    else
#endif
      parse_gps_msg();
    gps_msg_received = FALSE;
    if (gps_pos_available) {
      gps_verbose_downlink = !launch;
      UseGpsPosNoSend(estimator_update_state_gps);
      gps_downlink();
#ifdef GPS_TRIGGERED_FUNCTION
#ifndef SITL
    GPS_TRIGGERED_FUNCTION();
#endif
#endif
      gps_pos_available = FALSE;
    }
  }
#endif /** USE_GPS */


#if defined DATALINK

#if DATALINK == PPRZ
  if (PprzBuffer()) {
    ReadPprzBuffer();
    if (pprz_msg_received) {
      pprz_parse_payload();
      pprz_msg_received = FALSE;
    }
  }
#elif DATALINK == XBEE
  if (XBeeBuffer()) {
    ReadXBeeBuffer();
    if (xbee_msg_received) {
      xbee_parse_payload();
      xbee_msg_received = FALSE;
    }
  }
#else
#error "Unknown DATALINK"
#endif

  if (dl_msg_available) {
    dl_parse_msg();
    dl_msg_available = FALSE;
  }
#endif /** DATALINK */

#ifdef MCU_SPI_LINK
    link_mcu_event_task();
#endif

  if (inter_mcu_received_fbw) {
    /* receive radio control task from fbw */
    inter_mcu_received_fbw = FALSE;
    telecommand_task();
  }

  modules_event_task();
} /* event_task_ap() */