/** * Main task. It does not return. */ static void uavoTaranisTask(void *parameters) { while(1) { if (true) { // for some reason, only first four messages are sent. for (uint32_t i = 0; i < sizeof(frsky_value_items) / sizeof(frsky_value_items[0]); i++) { frsky->scheduled_item = i; frsky_send_scheduled_item(); PIOS_Thread_Sleep(5); } } if (false) { // fancier schedlued message sending. doesn't appear to work // currently. PIOS_Thread_Sleep(1); frsky_schedule_next_item(); frsky_send_scheduled_item(); } } }
static void uavoRelayTask(void *parameters) { UAVObjEvent ev; // Loop forever while (1) { PIOS_Thread_Sleep(50); // Wait for queue message if (PIOS_Queue_Receive(queue, &ev, 2) == true) { // Process event. This calls transmitData UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); } // Process incoming data in sufficient chunks that we keep up uint8_t serial_data[8]; uint16_t bytes_to_process; bytes_to_process = PIOS_COM_ReceiveBuffer(uavorelay_com_id, serial_data, sizeof(serial_data), 0); do { bytes_to_process = PIOS_COM_ReceiveBuffer(uavorelay_com_id, serial_data, sizeof(serial_data), 0); for (uint8_t i = 0; i < bytes_to_process; i++) UAVTalkProcessInputStream(uavTalkCon,serial_data[i]); } while (bytes_to_process > 0); } }
static void gpsConfigure(uint8_t gpsProtocol) { ModuleSettingsGPSAutoConfigureOptions gpsAutoConfigure; ModuleSettingsGPSAutoConfigureGet(&gpsAutoConfigure); if (gpsAutoConfigure != MODULESETTINGS_GPSAUTOCONFIGURE_TRUE) { return; } #if !defined(PIOS_GPS_MINIMAL) switch (gpsProtocol) { #if defined(PIOS_INCLUDE_GPS_UBX_PARSER) case MODULESETTINGS_GPSDATAPROTOCOL_UBX: { // Runs through a number of possible GPS baud rates to // configure the ublox baud rate. This uses a NMEA string // so could work for either UBX or NMEA actually. This is // somewhat redundant with updateSettings below, but that // is only called on startup and is not an issue. ModuleSettingsGPSSpeedOptions baud_rate; ModuleSettingsGPSConstellationOptions constellation; ModuleSettingsGPSSBASConstellationOptions sbas_const; ModuleSettingsGPSDynamicsModeOptions dyn_mode; ModuleSettingsGPSSpeedGet(&baud_rate); ModuleSettingsGPSConstellationGet(&constellation); ModuleSettingsGPSSBASConstellationGet(&sbas_const); ModuleSettingsGPSDynamicsModeGet(&dyn_mode); ubx_cfg_set_baudrate(gpsPort, baud_rate); PIOS_Thread_Sleep(1000); ubx_cfg_send_configuration(gpsPort, gps_rx_buffer, constellation, sbas_const, dyn_mode); } break; #endif } #endif /* PIOS_GPS_MINIMAL */ }
int main(int argc, char *argv[]) { PIOS_SYS_Args(argc, argv); #else int main() { #endif /* NOTE: Do NOT modify the following start-up sequence */ /* Any new initialization functions should be added in OpenPilotInit() */ PIOS_heap_initialize_blocks(); #if defined(PIOS_INCLUDE_CHIBIOS) halInit(); chSysInit(); boardInit(); #endif /* defined(PIOS_INCLUDE_CHIBIOS) */ /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); /* For Revolution we use a FreeRTOS task to bring up the system so we can */ /* always rely on FreeRTOS primitive */ initTaskHandle = PIOS_Thread_Create(initTask, "init", INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY); PIOS_Assert(initTaskHandle != NULL); #if defined(PIOS_INCLUDE_FREERTOS) /* Start the FreeRTOS scheduler */ vTaskStartScheduler(); /* If all is well we will never reach here as the scheduler will now be running. */ /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ for(;;) { \ PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ PIOS_DELAY_WaitmS(100); \ }; #elif defined(PIOS_INCLUDE_CHIBIOS) PIOS_Thread_Sleep(PIOS_THREAD_TIMEOUT_MAX); #endif /* defined(PIOS_INCLUDE_CHIBIOS) */ return 0; }
/* long ReceiveBuffer(unsigned char *,unsigned int,unsigned long): receives buffer from picoc serial port */ void SystemReceiveBuffer(struct ParseState *Parser, struct Value *ReturnValue, struct Value **Param, int NumArgs) { if ((PIOS_COM_PICOC) && (Param[0]->Val->Pointer != NULL)) { uint8_t *buffer = Param[0]->Val->Pointer; uint16_t buf_len = Param[1]->Val->UnsignedInteger; uint32_t timeout = Param[2]->Val->UnsignedLongInteger; ReturnValue->Val->LongInteger = 0; while (buf_len > 0) { uint16_t rc = PIOS_COM_ReceiveBuffer(PIOS_COM_PICOC, buffer, buf_len, 0); if (rc > 0) { buf_len -= rc; buffer += rc; ReturnValue->Val->LongInteger += rc; } else if (timeout-- > 0) { PIOS_Thread_Sleep(1); } else { return; } } } else { ReturnValue->Val->LongInteger = -1; } }
/* long SendBuffer(unsigned char *,unsigned int): sends a buffer content to picoc serial port */ void SystemSendBuffer(struct ParseState *Parser, struct Value *ReturnValue, struct Value **Param, int NumArgs) { if ((PIOS_COM_PICOC) && (Param[0]->Val->Pointer != NULL)) { uint8_t *buffer = Param[0]->Val->Pointer; uint16_t buf_len = Param[1]->Val->UnsignedInteger; ReturnValue->Val->LongInteger = 0; while (buf_len > 0) { int32_t rc = PIOS_COM_SendBufferNonBlocking(PIOS_COM_PICOC, buffer, buf_len); if (rc > 0) { buf_len -= rc; buffer += rc; ReturnValue->Val->LongInteger += rc; } else if (rc == 0) { PIOS_Thread_Sleep(1); } else { ReturnValue->Val->LongInteger = rc; return; } } } else { ReturnValue->Val->LongInteger = -1; } }
/** * Module thread, should not return. */ static void pathfollowerTask(void *parameters) { SystemSettingsData systemSettings; FlightStatusData flightStatus; uint32_t lastUpdateTime; AirspeedActualConnectCallback(airspeedActualUpdatedCb); FixedWingPathFollowerSettingsConnectCallback(SettingsUpdatedCb); FixedWingAirspeedsConnectCallback(SettingsUpdatedCb); PathDesiredConnectCallback(SettingsUpdatedCb); // Force update of all the settings SettingsUpdatedCb(NULL); FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); path_desired_updated = false; PathDesiredGet(&pathDesired); PathDesiredConnectCallback(pathDesiredUpdated); // Main task loop lastUpdateTime = PIOS_Thread_Systime(); while (1) { // Conditions when this runs: // 1. Must have FixedWing type airframe // 2. Flight mode is PositionHold and PathDesired.Mode is Endpoint OR // FlightMode is PathPlanner and PathDesired.Mode is Endpoint or Path SystemSettingsGet(&systemSettings); if ( (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWING) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGELEVON) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGVTAIL) ) { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_CRITICAL); PIOS_Thread_Sleep(1000); continue; } // Continue collecting data if not enough time PIOS_Thread_Sleep_Until(&lastUpdateTime, fixedwingpathfollowerSettings.UpdatePeriod); static uint8_t last_flight_mode; FlightStatusGet(&flightStatus); PathStatusGet(&pathStatus); PositionActualData positionActual; static enum {FW_FOLLOWER_IDLE, FW_FOLLOWER_RUNNING, FW_FOLLOWER_ERR} state = FW_FOLLOWER_IDLE; // Check whether an update to the path desired occured and we should // process it. This makes sure that the follower alarm state is // updated. bool process_path_desired_update = (last_flight_mode == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER || last_flight_mode == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && path_desired_updated; path_desired_updated = false; // Process most of these when the flight mode changes // except when in path following mode in which case // each iteration must make sure this has the latest // PathDesired if (flightStatus.FlightMode != last_flight_mode || process_path_desired_update) { last_flight_mode = flightStatus.FlightMode; switch(flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME: state = FW_FOLLOWER_RUNNING; PositionActualGet(&positionActual); pathDesired.Mode = PATHDESIRED_MODE_CIRCLEPOSITIONRIGHT; pathDesired.Start[0] = positionActual.North; pathDesired.Start[1] = positionActual.East; pathDesired.Start[2] = positionActual.Down; pathDesired.End[0] = 0; pathDesired.End[1] = 0; pathDesired.End[2] = -30.0f; pathDesired.ModeParameters = fixedwingpathfollowerSettings.OrbitRadius; pathDesired.StartingVelocity = fixedWingAirspeeds.CruiseSpeed; pathDesired.EndingVelocity = fixedWingAirspeeds.CruiseSpeed; PathDesiredSet(&pathDesired); break; case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: state = FW_FOLLOWER_RUNNING; PositionActualGet(&positionActual); pathDesired.Mode = PATHDESIRED_MODE_CIRCLEPOSITIONRIGHT; pathDesired.Start[0] = positionActual.North; pathDesired.Start[1] = positionActual.East; pathDesired.Start[2] = positionActual.Down; pathDesired.End[0] = positionActual.North; pathDesired.End[1] = positionActual.East; pathDesired.End[2] = positionActual.Down; pathDesired.ModeParameters = fixedwingpathfollowerSettings.OrbitRadius; pathDesired.StartingVelocity = fixedWingAirspeeds.CruiseSpeed; pathDesired.EndingVelocity = fixedWingAirspeeds.CruiseSpeed; PathDesiredSet(&pathDesired); break; case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: case FLIGHTSTATUS_FLIGHTMODE_TABLETCONTROL: state = FW_FOLLOWER_RUNNING; PathDesiredGet(&pathDesired); switch(pathDesired.Mode) { case PATHDESIRED_MODE_ENDPOINT: case PATHDESIRED_MODE_VECTOR: case PATHDESIRED_MODE_CIRCLERIGHT: case PATHDESIRED_MODE_CIRCLELEFT: break; default: state = FW_FOLLOWER_ERR; pathStatus.Status = PATHSTATUS_STATUS_CRITICAL; PathStatusSet(&pathStatus); AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_CRITICAL); break; } break; default: state = FW_FOLLOWER_IDLE; break; } } switch(state) { case FW_FOLLOWER_RUNNING: { updatePathVelocity(); uint8_t result = updateFixedDesiredAttitude(); if (result) { AlarmsClear(SYSTEMALARMS_ALARM_PATHFOLLOWER); } else { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_WARNING); } PathStatusSet(&pathStatus); break; } case FW_FOLLOWER_IDLE: // Be cleaner and get rid of global variables northVelIntegral = 0; eastVelIntegral = 0; downVelIntegral = 0; bearingIntegral = 0; speedIntegral = 0; accelIntegral = 0; powerIntegral = 0; airspeedErrorInt = 0; AlarmsClear(SYSTEMALARMS_ALARM_PATHFOLLOWER); break; case FW_FOLLOWER_ERR: default: // Leave alarms set above break; } } }
/** * Module thread, should not return. */ static void groundPathFollowerTask(void *parameters) { SystemSettingsData systemSettings; FlightStatusData flightStatus; uint32_t lastUpdateTime; GroundPathFollowerSettingsConnectCallback(SettingsUpdatedCb); PathDesiredConnectCallback(SettingsUpdatedCb); GroundPathFollowerSettingsGet(&guidanceSettings); PathDesiredGet(&pathDesired); // Main task loop lastUpdateTime = PIOS_Thread_Systime(); while (1) { // Conditions when this runs: // 1. Must have GROUND type airframe // 2. Flight mode is PositionHold and PathDesired.Mode is Endpoint OR // FlightMode is PathPlanner and PathDesired.Mode is Endpoint or Path SystemSettingsGet(&systemSettings); if ( (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLECAR) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE) ) { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_WARNING); PIOS_Thread_Sleep(1000); continue; } // Continue collecting data if not enough time PIOS_Thread_Sleep_Until(&lastUpdateTime, guidanceSettings.UpdatePeriod); // Convert the accels into the NED frame updateNedAccel(); FlightStatusGet(&flightStatus); // Check the combinations of flightmode and pathdesired mode switch(flightStatus.FlightMode) { /* This combination of RETURNTOHOME and HOLDPOSITION looks strange but * is correct. RETURNTOHOME mode uses HOLDPOSITION with the position * set to home */ case FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME: if (pathDesired.Mode == PATHDESIRED_MODE_HOLDPOSITION) { updateEndpointVelocity(); updateGroundDesiredAttitude(); } else { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_ERROR); } break; case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: if (pathDesired.Mode == PATHDESIRED_MODE_HOLDPOSITION) { updateEndpointVelocity(); updateGroundDesiredAttitude(); } else { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_ERROR); } break; case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: if (pathDesired.Mode == PATHDESIRED_MODE_FLYENDPOINT || pathDesired.Mode == PATHDESIRED_MODE_HOLDPOSITION) { updateEndpointVelocity(); updateGroundDesiredAttitude(); } else if (pathDesired.Mode == PATHDESIRED_MODE_FLYVECTOR || pathDesired.Mode == PATHDESIRED_MODE_FLYCIRCLELEFT || pathDesired.Mode == PATHDESIRED_MODE_FLYCIRCLERIGHT) { updatePathVelocity(); updateGroundDesiredAttitude(); } else { AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER,SYSTEMALARMS_ALARM_ERROR); } break; default: // Be cleaner and get rid of global variables northVelIntegral = 0; eastVelIntegral = 0; northPosIntegral = 0; eastPosIntegral = 0; // Track throttle before engaging this mode. Cheap system ident StabilizationDesiredData stabDesired; StabilizationDesiredGet(&stabDesired); throttleOffset = stabDesired.Throttle; break; } AlarmsClear(SYSTEMALARMS_ALARM_PATHFOLLOWER); } }
static void loggingTask(void *parameters) { UAVObjEvent ev; bool armed = false; uint32_t now = PIOS_Thread_Systime(); #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) bool write_open = false; bool read_open = false; int32_t read_sector = 0; uint8_t read_data[LOGGINGSTATS_FILESECTOR_NUMELEM]; #endif // Get settings automatically for now on LoggingSettingsConnectCopy(&settings); LoggingStatsGet(&loggingData); loggingData.BytesLogged = 0; #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) if (destination_spi_flash) { loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); } #endif if (settings.LogBehavior == LOGGINGSETTINGS_LOGBEHAVIOR_LOGONSTART) { loggingData.Operation = LOGGINGSTATS_OPERATION_INITIALIZING; } else { loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } LoggingStatsSet(&loggingData); // Loop forever while (1) { LoggingStatsGet(&loggingData); // Check for change in armed state if logging on armed if (settings.LogBehavior == LOGGINGSETTINGS_LOGBEHAVIOR_LOGONARM) { FlightStatusData flightStatus; FlightStatusGet(&flightStatus); if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED && !armed) { // Start logging because just armed loggingData.Operation = LOGGINGSTATS_OPERATION_INITIALIZING; armed = true; LoggingStatsSet(&loggingData); } else if (flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED && armed) { loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; armed = false; LoggingStatsSet(&loggingData); } } switch (loggingData.Operation) { case LOGGINGSTATS_OPERATION_FORMAT: // Format the file system #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) if (destination_spi_flash){ if (read_open || write_open) { PIOS_STREAMFS_Close(streamfs_id); read_open = false; write_open = false; } PIOS_STREAMFS_Format(streamfs_id); loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); } #endif /* defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) */ loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; LoggingStatsSet(&loggingData); break; case LOGGINGSTATS_OPERATION_INITIALIZING: // Unregister all objects UAVObjIterate(&unregister_object); // Register objects to be logged switch (settings.Profile) { case LOGGINGSETTINGS_PROFILE_DEFAULT: register_default_profile(); break; case LOGGINGSETTINGS_PROFILE_CUSTOM: UAVObjIterate(®ister_object); break; } #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) if (destination_spi_flash){ // Close the file if it is open for reading if (read_open) { PIOS_STREAMFS_Close(streamfs_id); read_open = false; } // Open the file if it is not open for writing if (!write_open) { if (PIOS_STREAMFS_OpenWrite(streamfs_id) != 0) { loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; continue; } else { write_open = true; } loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); LoggingStatsSet(&loggingData); } } else { read_open = false; write_open = true; } #endif /* defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) */ // Write information at start of the log file writeHeader(); // Log settings if (settings.LogSettingsOnStart == LOGGINGSETTINGS_LOGSETTINGSONSTART_TRUE){ UAVObjIterate(&logSettings); } // Empty the queue while(PIOS_Queue_Receive(logging_queue, &ev, 0)) LoggingStatsBytesLoggedSet(&written_bytes); loggingData.Operation = LOGGINGSTATS_OPERATION_LOGGING; LoggingStatsSet(&loggingData); break; case LOGGINGSTATS_OPERATION_LOGGING: { // Sleep between writing PIOS_Thread_Sleep_Until(&now, LOGGING_PERIOD_MS); // Log the objects registred to the shared queue for (int i=0; i<LOGGING_QUEUE_SIZE; i++) { if (PIOS_Queue_Receive(logging_queue, &ev, 0) == true) { UAVTalkSendObjectTimestamped(uavTalkCon, ev.obj, ev.instId, false, 0); } else { break; } } LoggingStatsBytesLoggedSet(&written_bytes); now = PIOS_Thread_Systime(); } break; case LOGGINGSTATS_OPERATION_DOWNLOAD: #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) if (destination_spi_flash) { if (!read_open) { // Start reading if (PIOS_STREAMFS_OpenRead(streamfs_id, loggingData.FileRequest) != 0) { loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; } else { read_open = true; read_sector = -1; } } if (read_open && read_sector == loggingData.FileSectorNum) { // Request received for same sector. Reupdate. memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } else if (read_open && (read_sector + 1) == loggingData.FileSectorNum) { int32_t bytes_read = PIOS_COM_ReceiveBuffer(logging_com_id, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM, 1); if (bytes_read < 0 || bytes_read > LOGGINGSTATS_FILESECTOR_NUMELEM) { // close on error loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; PIOS_STREAMFS_Close(streamfs_id); read_open = false; } else if (bytes_read < LOGGINGSTATS_FILESECTOR_NUMELEM) { // Check it has really run out of bytes by reading again int32_t bytes_read2 = PIOS_COM_ReceiveBuffer(logging_com_id, &read_data[bytes_read], LOGGINGSTATS_FILESECTOR_NUMELEM - bytes_read, 1); memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); if ((bytes_read + bytes_read2) < LOGGINGSTATS_FILESECTOR_NUMELEM) { // indicate end of file loggingData.Operation = LOGGINGSTATS_OPERATION_COMPLETE; PIOS_STREAMFS_Close(streamfs_id); read_open = false; } else { // Indicate sent loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } } else { // Indicate sent loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); } read_sector = loggingData.FileSectorNum; } LoggingStatsSet(&loggingData); } #endif /* defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) */ // fall-through to default case default: // Makes sure that we are not hogging the processor PIOS_Thread_Sleep(10); #if defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) if (destination_spi_flash) { // Close the file if necessary if (write_open) { PIOS_STREAMFS_Close(streamfs_id); loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); LoggingStatsSet(&loggingData); write_open = false; } } #endif /* defined(PIOS_INCLUDE_FLASH) && defined(PIOS_INCLUDE_FLASH_JEDEC) */ } } }
/** * Function called in response to object updates */ static void objectUpdatedCb(UAVObjEvent * ev) { ObjectPersistenceData objper; UAVObjHandle obj; // If the object updated was the ObjectPersistence execute requested action if (ev->obj == ObjectPersistenceHandle()) { // Get object data ObjectPersistenceGet(&objper); int retval = 1; // When this is called because of this method don't do anything if (objper.Operation == OBJECTPERSISTENCE_OPERATION_ERROR || objper.Operation == OBJECTPERSISTENCE_OPERATION_COMPLETED) { return; } if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) { if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) { // Get selected object obj = UAVObjGetByID(objper.ObjectID); if (obj == 0) { return; } // Load selected instance retval = UAVObjLoad(obj, objper.InstanceID); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjLoadSettings(); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLMETAOBJECTS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjLoadMetaobjects(); } } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_SAVE) { if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) { // Get selected object obj = UAVObjGetByID(objper.ObjectID); if (obj == 0) { return; } // Save selected instance retval = UAVObjSave(obj, objper.InstanceID); // Not sure why this is needed PIOS_Thread_Sleep(10); // Verify saving worked if (retval == 0) retval = UAVObjLoad(obj, objper.InstanceID); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjSaveSettings(); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLMETAOBJECTS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjSaveMetaobjects(); } } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_DELETE) { if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) { // Delete selected instance retval = UAVObjDeleteById(objper.ObjectID, objper.InstanceID); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjDeleteSettings(); } else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLMETAOBJECTS || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjDeleteMetaobjects(); } } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) { retval = -1; #if defined(PIOS_INCLUDE_LOGFS_SETTINGS) extern uintptr_t pios_uavo_settings_fs_id; retval = PIOS_FLASHFS_Format(pios_uavo_settings_fs_id); #endif } switch(retval) { case 0: objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED; ObjectPersistenceSet(&objper); break; case -1: objper.Operation = OBJECTPERSISTENCE_OPERATION_ERROR; ObjectPersistenceSet(&objper); break; default: break; } } }
/** * Module thread, should not return. */ static void AutotuneTask(void *parameters) { enum AUTOTUNE_STATE state = AT_INIT; uint32_t last_update_time = PIOS_Thread_Systime(); float X[AF_NUMX] = {0}; float P[AF_NUMP] = {0}; float noise[3] = {0}; af_init(X,P); uint32_t last_time = 0.0f; const uint32_t YIELD_MS = 2; GyrosConnectCallback(at_new_gyro_data); while(1) { PIOS_WDG_UpdateFlag(PIOS_WDG_AUTOTUNE); uint32_t diff_time; const uint32_t PREPARE_TIME = 2000; const uint32_t MEASURE_TIME = 60000; static uint32_t update_counter = 0; bool doing_ident = false; bool can_sleep = true; FlightStatusData flightStatus; FlightStatusGet(&flightStatus); // Only allow this module to run when autotuning if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) { state = AT_INIT; PIOS_Thread_Sleep(50); continue; } switch(state) { case AT_INIT: last_update_time = PIOS_Thread_Systime(); // Only start when armed and flying if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { af_init(X,P); UpdateSystemIdent(X, NULL, 0.0f, 0, 0); state = AT_START; } break; case AT_START: diff_time = PIOS_Thread_Systime() - last_update_time; // Spend the first block of time in normal rate mode to get airborne if (diff_time > PREPARE_TIME) { last_time = PIOS_DELAY_GetRaw(); /* Drain the queue of all current data */ while (circ_queue_read_pos(at_queue)) { circ_queue_read_completed(at_queue); } /* And reset the point spill counter */ update_counter = 0; at_points_spilled = 0; state = AT_RUN; last_update_time = PIOS_Thread_Systime(); } break; case AT_RUN: diff_time = PIOS_Thread_Systime() - last_update_time; doing_ident = true; can_sleep = false; for (int i=0; i<MAX_PTS_PER_CYCLE; i++) { struct at_queued_data *pt; /* Grab an autotune point */ pt = circ_queue_read_pos(at_queue); if (!pt) { /* We've drained the buffer * fully. Yay! */ can_sleep = true; break; } /* calculate time between successive * points */ float dT_s = PIOS_DELAY_DiffuS2(last_time, pt->raw_time) * 1.0e-6f; /* This is for the first point, but * also if we have extended drops */ if (dT_s > 0.010f) { dT_s = 0.010f; } last_time = pt->raw_time; af_predict(X, P, pt->u, pt->y, dT_s); // Update uavo every 256 cycles to avoid // telemetry spam if (!((update_counter++) & 0xff)) { UpdateSystemIdent(X, noise, dT_s, update_counter, at_points_spilled); } for (uint32_t i = 0; i < 3; i++) { const float NOISE_ALPHA = 0.9997f; // 10 second time constant at 300 Hz noise[i] = NOISE_ALPHA * noise[i] + (1-NOISE_ALPHA) * (pt->y[i] - X[i]) * (pt->y[i] - X[i]); } /* Free the buffer containing an AT point */ circ_queue_read_completed(at_queue); } if (diff_time > MEASURE_TIME) { // Move on to next state state = AT_FINISHED; last_update_time = PIOS_Thread_Systime(); } break; case AT_FINISHED: // Wait until disarmed and landed before saving the settings UpdateSystemIdent(X, noise, 0, update_counter, at_points_spilled); state = AT_WAITING; // Fall through case AT_WAITING: // TODO do this unconditionally on disarm, // no matter what mode we're in. if (flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED) { // Save the settings locally. UAVObjSave(SystemIdentHandle(), 0); state = AT_INIT; } break; default: // Set an alarm or some shit like that break; } // Update based on manual controls UpdateStabilizationDesired(doing_ident); if (can_sleep) { PIOS_Thread_Sleep(YIELD_MS); } } }
static void loggingTask(void *parameters) { bool armed = false; bool write_open = false; bool read_open = false; int32_t read_sector = 0; uint8_t read_data[LOGGINGSTATS_FILESECTOR_NUMELEM]; //PIOS_STREAMFS_Format(streamfs_id); LoggingStatsData loggingData; LoggingStatsGet(&loggingData); loggingData.BytesLogged = 0; loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); LoggingSettingsData settings; LoggingSettingsGet(&settings); if (settings.LogBehavior == LOGGINGSETTINGS_LOGBEHAVIOR_LOGONSTART) { if (PIOS_STREAMFS_OpenWrite(streamfs_id) != 0) { loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; write_open = false; } else { loggingData.Operation = LOGGINGSTATS_OPERATION_LOGGING; write_open = true; } } else { loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } LoggingStatsSet(&loggingData); int i = 0; // Loop forever while (1) { // Do not update anything at more than 40 Hz PIOS_Thread_Sleep(20); LoggingStatsGet(&loggingData); // Check for change in armed state if logging on armed LoggingSettingsGet(&settings); if (settings.LogBehavior == LOGGINGSETTINGS_LOGBEHAVIOR_LOGONARM) { FlightStatusData flightStatus; FlightStatusGet(&flightStatus); if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED && !armed) { // Start logging because just armed loggingData.Operation = LOGGINGSTATS_OPERATION_LOGGING; armed = true; LoggingStatsSet(&loggingData); } else if (flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED && armed) { loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; armed = false; LoggingStatsSet(&loggingData); } } // If currently downloading a log, close the file if (loggingData.Operation == LOGGINGSTATS_OPERATION_LOGGING && read_open) { PIOS_STREAMFS_Close(streamfs_id); read_open = false; } if (loggingData.Operation == LOGGINGSTATS_OPERATION_LOGGING && !write_open) { if (PIOS_STREAMFS_OpenWrite(streamfs_id) != 0) { loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; } else { write_open = true; } loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); LoggingStatsSet(&loggingData); } else if (loggingData.Operation != LOGGINGSTATS_OPERATION_LOGGING && write_open) { PIOS_STREAMFS_Close(streamfs_id); loggingData.MinFileId = PIOS_STREAMFS_MinFileId(streamfs_id); loggingData.MaxFileId = PIOS_STREAMFS_MaxFileId(streamfs_id); LoggingStatsSet(&loggingData); write_open = false; } switch (loggingData.Operation) { case LOGGINGSTATS_OPERATION_LOGGING: if (!write_open) continue; UAVTalkSendObjectTimestamped(uavTalkCon, AttitudeActualHandle(), 0, false, 0); UAVTalkSendObjectTimestamped(uavTalkCon, AccelsHandle(), 0, false, 0); UAVTalkSendObjectTimestamped(uavTalkCon, GyrosHandle(), 0, false, 0); UAVTalkSendObjectTimestamped(uavTalkCon, MagnetometerHandle(), 0, false, 0); if ((i % 10) == 0) { UAVTalkSendObjectTimestamped(uavTalkCon, BaroAltitudeHandle(), 0, false, 0); UAVTalkSendObjectTimestamped(uavTalkCon, GPSPositionHandle(), 0, false, 0); } if ((i % 50) == 1) { UAVTalkSendObjectTimestamped(uavTalkCon, GPSTimeHandle(), 0, false, 0); } LoggingStatsBytesLoggedSet(&written_bytes); break; case LOGGINGSTATS_OPERATION_DOWNLOAD: if (!read_open) { // Start reading if (PIOS_STREAMFS_OpenRead(streamfs_id, loggingData.FileRequest) != 0) { loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; } else { read_open = true; read_sector = -1; } } if (read_open && read_sector == loggingData.FileSectorNum) { // Request received for same sector. Reupdate. memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } else if (read_open && (read_sector + 1) == loggingData.FileSectorNum) { int32_t bytes_read = PIOS_COM_ReceiveBuffer(logging_com_id, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM, 1); if (bytes_read < 0 || bytes_read > LOGGINGSTATS_FILESECTOR_NUMELEM) { // close on error loggingData.Operation = LOGGINGSTATS_OPERATION_ERROR; PIOS_STREAMFS_Close(streamfs_id); read_open = false; } else if (bytes_read < LOGGINGSTATS_FILESECTOR_NUMELEM) { // Check it has really run out of bytes by reading again int32_t bytes_read2 = PIOS_COM_ReceiveBuffer(logging_com_id, &read_data[bytes_read], LOGGINGSTATS_FILESECTOR_NUMELEM - bytes_read, 1); memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); if ((bytes_read + bytes_read2) < LOGGINGSTATS_FILESECTOR_NUMELEM) { // indicate end of file loggingData.Operation = LOGGINGSTATS_OPERATION_COMPLETE; PIOS_STREAMFS_Close(streamfs_id); read_open = false; } else { // Indicate sent loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; } } else { // Indicate sent loggingData.Operation = LOGGINGSTATS_OPERATION_IDLE; memcpy(loggingData.FileSector, read_data, LOGGINGSTATS_FILESECTOR_NUMELEM); } read_sector = loggingData.FileSectorNum; } LoggingStatsSet(&loggingData); } i++; } }
/* void delay(int): sleep for given ms-value */ void SystemDelay(struct ParseState *Parser, struct Value *ReturnValue, struct Value **Param, int NumArgs) { if (Param[0]->Val->Integer > 0) { PIOS_Thread_Sleep(Param[0]->Val->Integer); } }
//! Make sure the GPS is set to the same baudrate as the port void ubx_cfg_set_baudrate(uintptr_t gps_port, ModuleSettingsGPSSpeedOptions baud_rate) { // UBX,41 msg // 1 - portID // 0007 - input protocol (all) // 0001 - output protocol (ubx only) // 0 - no attempt to autobaud // number - baudrate // *XX - checksum const char * msg_2400 = "$PUBX,41,1,0007,0001,2400,0*1B\r\n"; const char * msg_4800 = "$PUBX,41,1,0007,0001,4800,0*11\r\n"; const char * msg_9600 = "$PUBX,41,1,0007,0001,9600,0*12\r\n"; const char * msg_19200 = "$PUBX,41,1,0007,0001,19200,0*27\r\n"; const char * msg_38400 = "$PUBX,41,1,0007,0001,38400,0*22\r\n"; const char * msg_57600 = "$PUBX,41,1,0007,0001,57600,0*29\r\n"; const char * msg_115200 = "$PUBX,41,1,0007,0001,115200,0*1A\r\n"; const char * msg_230400 = "$PUBX,41,1,0007,0001,230400,0*18\r\n"; const char *msg; uint32_t baud; switch (baud_rate) { case MODULESETTINGS_GPSSPEED_2400: msg = msg_2400; baud = 2400; break; case MODULESETTINGS_GPSSPEED_4800: msg = msg_4800; baud = 4800; break; case MODULESETTINGS_GPSSPEED_9600: msg = msg_9600; baud = 9600; break; case MODULESETTINGS_GPSSPEED_19200: msg = msg_19200; baud = 19200; break; case MODULESETTINGS_GPSSPEED_38400: msg = msg_38400; baud = 38400; break; default: case MODULESETTINGS_GPSSPEED_57600: msg = msg_57600; baud = 57600; break; case MODULESETTINGS_GPSSPEED_115200: msg = msg_115200; baud = 115200; break; case MODULESETTINGS_GPSSPEED_230400: msg = msg_230400; baud = 230400; break; } // Attempt to set baud rate to desired value from a number of // common rates. So this configures the physical baudrate and // tries to send the configuration string to the GPS. const uint32_t baud_rates[] = {2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400}; for (uint32_t i = 0; i < NELEMENTS(baud_rates); i++) { PIOS_COM_ChangeBaud(gps_port, baud_rates[i]); PIOS_Thread_Sleep(UBLOX_WAIT_MS); // Send the baud rate change message PIOS_COM_SendString(gps_port, msg); // Wait until the message has been fully transmitted including all start+stop bits // 34 bytes * 10bits/byte = 340 bits // At 2400bps, that's (340 / 2400) = 142ms // add some margin and we end up with 200ms PIOS_Thread_Sleep(200); } // Set to proper baud rate PIOS_COM_ChangeBaud(gps_port, baud); }
static void gpsTask(void *parameters) { GPSPositionData gpsposition; uint32_t timeOfLastUpdateMs = 0; uint32_t timeOfConfigAttemptMs = 0; uint8_t gpsProtocol; #ifdef PIOS_GPS_PROVIDES_AIRSPEED gps_airspeed_initialize(); #endif GPSPositionGet(&gpsposition); // Wait for power to stabilize before talking to external devices PIOS_Thread_Sleep(1000); // Loop forever while (1) { uint32_t xDelay = GPS_COM_TIMEOUT_MS; uint32_t loopTimeMs = PIOS_Thread_Systime(); // XXX TODO: also on modulesettings change.. if (!timeOfConfigAttemptMs) { ModuleSettingsGPSDataProtocolGet(&gpsProtocol); gpsConfigure(gpsProtocol); timeOfConfigAttemptMs = PIOS_Thread_Systime(); continue; } uint8_t c; // This blocks the task until there is something on the buffer while (PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, xDelay) > 0) { int res; switch (gpsProtocol) { #if defined(PIOS_INCLUDE_GPS_NMEA_PARSER) case MODULESETTINGS_GPSDATAPROTOCOL_NMEA: res = parse_nmea_stream (c,gps_rx_buffer, &gpsposition, &gpsRxStats); break; #endif #if defined(PIOS_INCLUDE_GPS_UBX_PARSER) case MODULESETTINGS_GPSDATAPROTOCOL_UBX: res = parse_ubx_stream (c,gps_rx_buffer, &gpsposition, &gpsRxStats); break; #endif default: res = NO_PARSER; // this should not happen break; } if (res == PARSER_COMPLETE) { timeOfLastUpdateMs = loopTimeMs; } xDelay = 0; // For now on, don't block / wait, // but consume what we can from the fifo } // Check for GPS timeout if ((loopTimeMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS) { // we have not received any valid GPS sentences for a while. // either the GPS is not plugged in or a hardware problem or the GPS has locked up. uint8_t status = GPSPOSITION_STATUS_NOGPS; GPSPositionStatusSet(&status); AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); /* Don't reinitialize too often. */ if ((loopTimeMs - timeOfConfigAttemptMs) >= GPS_TIMEOUT_MS) { timeOfConfigAttemptMs = 0; // reinit next loop } } else { // we appear to be receiving GPS sentences OK, we've had an update //criteria for GPS-OK taken from this post if (gpsposition.PDOP < 3.5f && gpsposition.Satellites >= 7 && (gpsposition.Status == GPSPOSITION_STATUS_FIX3D || gpsposition.Status == GPSPOSITION_STATUS_DIFF3D)) { AlarmsClear(SYSTEMALARMS_ALARM_GPS); } else if (gpsposition.Status == GPSPOSITION_STATUS_FIX3D || gpsposition.Status == GPSPOSITION_STATUS_DIFF3D) AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); else AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); } } }
/** * Module task */ static void pathPlannerTask(void *parameters) { // If the PathStatus isn't available no follower is running and we should abort while (PathStatusHandle() == NULL || !TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { AlarmsSet(SYSTEMALARMS_ALARM_PATHPLANNER, SYSTEMALARMS_ALARM_CRITICAL); PIOS_Thread_Sleep(1000); } AlarmsClear(SYSTEMALARMS_ALARM_PATHPLANNER); PathPlannerSettingsConnectCallback(settingsUpdated); settingsUpdated(PathPlannerSettingsHandle()); WaypointConnectCallback(waypointsUpdated); WaypointActiveConnectCallback(waypointsUpdated); PathStatusConnectCallback(pathStatusUpdated); FlightStatusData flightStatus; // Main thread loop bool pathplanner_active = false; path_status_updated = false; while (1) { PIOS_Thread_Sleep(UPDATE_RATE_MS); // When not running the path planner short circuit and wait FlightStatusGet(&flightStatus); if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) { pathplanner_active = false; continue; } if(pathplanner_active == false) { // Reset the state. Active waypoint should be set to an invalid // value to force waypoint 0 to become activated when starting // Note: this needs to be done before the callback is triggered! active_waypoint = -1; previous_waypoint = -1; // This triggers callback to update variable WaypointActiveGet(&waypointActive); waypointActive.Index = 0; WaypointActiveSet(&waypointActive); pathplanner_active = true; continue; } /* This method determines if we have achieved the goal of the active */ /* waypoint */ if (path_status_updated) checkTerminationCondition(); /* If advance waypoint takes a long time to calculate then it should */ /* be called from here when the active_waypoints does not equal the */ /* WaypointActive.Index */ /* if (active_waypoint != WaypointActive.Index) */ /* advanceWaypoint(WaypointActive.Index) */ } }