1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-21 11:54:15 +01:00

Merge branch 'master' into OP-483_os_release-packaging

This commit is contained in:
Oleg Semyonov 2011-05-15 21:32:20 +03:00
commit 39d4f23b67
31 changed files with 5316 additions and 4909 deletions

View File

@ -105,6 +105,11 @@ C: Gary Mortimer and the Scorpion
D: March 2011 D: March 2011
V: http://vimeo.com/22104334 V: http://vimeo.com/22104334
M: First Y6 OpenPilot flight
C: Sami Korhonen (Sambas)
D: May 2011
V: http://www.vimeo.com/23637586
M: First CopterControl flight on a Flybarless Heli M: First CopterControl flight on a Flybarless Heli
C: ? C: ?
D: ? D: ?

View File

@ -205,6 +205,7 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
## PIOS Hardware (Common) ## PIOS Hardware (Common)
SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c
SRC += $(PIOSCOMMON)/pios_flash_w25x.c SRC += $(PIOSCOMMON)/pios_flash_w25x.c
SRC += $(PIOSCOMMON)/pios_adxl345.c SRC += $(PIOSCOMMON)/pios_adxl345.c
SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_com.c

View File

@ -92,6 +92,7 @@ void OpenPilotInit()
#ifdef ERASE_FLASH #ifdef ERASE_FLASH
PIOS_Flash_W25X_EraseChip(); PIOS_Flash_W25X_EraseChip();
while(TRUE){};
#endif #endif
/* Initialize modules */ /* Initialize modules */

View File

@ -678,8 +678,10 @@ void PIOS_Board_Init(void) {
PIOS_DEBUG_Assert(0); PIOS_DEBUG_Assert(0);
} }
PIOS_Flash_W25X_Init(pios_spi_flash_accel_id); PIOS_Flash_W25X_Init(pios_spi_flash_accel_id);
PIOS_ADXL345_Attach(pios_spi_flash_accel_id); PIOS_ADXL345_Attach(pios_spi_flash_accel_id);
PIOS_FLASHFS_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM) #if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */ /* SPEKTRUM init must come before comms */

View File

@ -141,18 +141,19 @@ static void AttitudeTask(void *parameters)
FlightStatusData flightStatus; FlightStatusData flightStatus;
FlightStatusGet(&flightStatus); FlightStatusGet(&flightStatus);
if(xTaskGetTickCount() < 10000) { if(xTaskGetTickCount() < 7000) {
// For first 5 seconds use accels to get gyro bias // Force settings update to make sure rotation loaded
settingsUpdatedCb(AttitudeSettingsHandle());
// For first 7 seconds use accels to get gyro bias
accelKp = 1; accelKp = 1;
// Decrease the rate of gyro learning during init accelKi = 0.9;
accelKi = .5 / (1 + xTaskGetTickCount() / 5000); yawBiasRate = 0.23;
yawBiasRate = 0.01 / (1 + xTaskGetTickCount() / 5000);
init = 0; init = 0;
} }
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
accelKi = .01; accelKi = 0.9;
yawBiasRate = 0.1; yawBiasRate = 0.23;
init = 0; init = 0;
} else if (init == 0) { } else if (init == 0) {
settingsUpdatedCb(AttitudeSettingsHandle()); settingsUpdatedCb(AttitudeSettingsHandle());

View File

@ -30,6 +30,7 @@
#include "openpilot.h" #include "openpilot.h"
#include "firmwareiap.h" #include "firmwareiap.h"
#include "firmwareiapobj.h" #include "firmwareiapobj.h"
#include "flightstatus.h"
// Private constants // Private constants
#define IAP_CMD_STEP_1 1122 #define IAP_CMD_STEP_1 1122
@ -156,6 +157,16 @@ static void FirmwareIAPCallback(UAVObjEvent* ev)
case IAP_STATE_STEP_2: case IAP_STATE_STEP_2:
if( data.Command == IAP_CMD_STEP_3 ) { if( data.Command == IAP_CMD_STEP_3 ) {
if( delta > iap_time_3_low_end && delta < iap_time_3_high_end ) { if( delta > iap_time_3_low_end && delta < iap_time_3_high_end ) {
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) {
// Abort any attempts if not disarmed
iap_state = IAP_STATE_READY;
break;
}
// we've met the three sequence of command numbers // we've met the three sequence of command numbers
// we've met the time requirements. // we've met the time requirements.
PIOS_IAP_SetRequest1(); PIOS_IAP_SetRequest1();

View File

@ -63,7 +63,7 @@ static float GravityAccel(float latitude, float longitude, float altitude);
// Private constants // Private constants
//#define FULL_COLD_RESTART // uncomment this to tell the GPS to do a FULL COLD restart //#define FULL_COLD_RESTART // uncomment this to tell the GPS to do a FULL COLD restart
//#define DISABLE_GPS_TRESHOLD // //#define DISABLE_GPS_THRESHOLD //
#define GPS_TIMEOUT_MS 500 #define GPS_TIMEOUT_MS 500
#define GPS_COMMAND_RESEND_TIMEOUT_MS 2000 #define GPS_COMMAND_RESEND_TIMEOUT_MS 2000
@ -154,7 +154,7 @@ static void gpsTask(void *parameters)
} }
#endif #endif
#ifdef DISABLE_GPS_TRESHOLD #ifdef DISABLE_GPS_THRESHOLD
PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n"); PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n");
#endif #endif

View File

@ -52,14 +52,13 @@ endif
FLASH_TOOL = OPENOCD FLASH_TOOL = OPENOCD
# List of modules to include # List of modules to include
MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP FlightPlan MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP
PYMODULES = FlightPlan
#MODULES = Telemetry Example #MODULES = Telemetry Example
#MODULES = Telemetry MK/MKSerial #MODULES = Telemetry MK/MKSerial
#MODULES = Telemetry #MODULES = Telemetry
#MODULES += Osd/OsdEtStd #MODULES += Osd/OsdEtStd
# MCU name, submodel and board # MCU name, submodel and board
# - MCU used for compiler-option (-mcpu) # - MCU used for compiler-option (-mcpu)
# - MODEL used for linker-script name (-T) and passed as define # - MODEL used for linker-script name (-T) and passed as define
@ -124,17 +123,19 @@ UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
# List C source files here. (C dependencies are automatically generated.) # List C source files here. (C dependencies are automatically generated.)
# use file-extension c for "c-only"-files # use file-extension c for "c-only"-files
MODNAMES = $(notdir ${MODULES}) MODNAMES = $(notdir ${MODULES} ${PYMODULES})
ifndef TESTAPP ifndef TESTAPP
## PyMite files ## PyMite files and modules
SRC += $(OUTDIR)/pmlib_img.c SRC += $(OUTDIR)/pmlib_img.c
SRC += $(OUTDIR)/pmlib_nat.c SRC += $(OUTDIR)/pmlib_nat.c
SRC += $(OUTDIR)/pmlibusr_img.c SRC += $(OUTDIR)/pmlibusr_img.c
SRC += $(OUTDIR)/pmlibusr_nat.c SRC += $(OUTDIR)/pmlibusr_nat.c
SRC += $(wildcard ${PYMITEVM}/*.c) PYSRC += $(wildcard ${PYMITEVM}/*.c)
SRC += $(wildcard ${PYMITEPLAT}/*.c) PYSRC += $(wildcard ${PYMITEPLAT}/*.c)
PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
SRC += $(PYSRC)
## MODULES ## MODULES
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
@ -317,7 +318,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(PYMITEINC)
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
# List any extra directories to look for library files here. # List any extra directories to look for library files here.
@ -481,7 +482,7 @@ LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
# Default target. # Default target.
all: gencode gccversion build all: gccversion build
ifeq ($(LOADFORMAT),ihex) ifeq ($(LOADFORMAT),ihex)
build: elf hex lss sym build: elf hex lss sym
@ -500,6 +501,8 @@ endif
# Generate intermediate code # Generate intermediate code
gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
$(PYSRC): gencode
# Generate code for module initialization # Generate code for module initialization
${OUTDIR}/InitMods.c: Makefile ${OUTDIR}/InitMods.c: Makefile
@echo $(MSG_MODINIT) $(call toprel, $@) @echo $(MSG_MODINIT) $(call toprel, $@)

View File

@ -222,6 +222,14 @@ int8_t PIOS_Flash_W25X_WriteData(uint32_t addr, uint8_t * data, uint16_t len)
return 0; return 0;
} }
/**
* @brief Read data from a location in flash memory
* @param[in] addr Address in flash to write to
* @param[in] data Pointer to data to write from flash
* @param[in] len Length of data to write (max 256 bytes)
* @return Zero if success or error code
* @retval -1 Unable to claim SPI bus
*/
int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len) int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len)
{ {
if(PIOS_Flash_W25X_ClaimBus() == -1) if(PIOS_Flash_W25X_ClaimBus() == -1)

View File

@ -0,0 +1,294 @@
/**
******************************************************************************
*
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_FLASHFS_OBJLIST Object list based flash filesystem (low ram)
* @{
*
* @file pios_flashfs_objlist.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief A file system for storing UAVObject in flash chip
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "openpilot.h"
#include "uavobjectmanager.h"
// Private functions
static int32_t PIOS_FLASHFS_CleabObjectTableHeader();
static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId);
static int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId);
// Private variables
static int32_t numObjects = -1;
// Private structures
// Header for objects in the file system table
struct objectHeader {
uint32_t objMagic;
uint32_t objId;
uint32_t instId;
uint32_t address;
} __attribute__((packed));;
struct fileHeader {
uint32_t id;
uint16_t instId;
uint16_t size;
} __attribute__((packed));
#define OBJECT_TABLE_MAGIC 0x85FB3C33
#define OBJ_MAGIC 0x3015AE71
#define OBJECT_TABLE_START 0x00000010
#define OBJECT_TABLE_END 0x00001000
#define SECTOR_SIZE 0x00001000
/**
* @brief Initialize the flash object setting FS
* @return 0 if success, -1 if failure
*/
int32_t PIOS_FLASHFS_Init()
{
// Check for valid object table or create one
uint32_t object_table_magic;
if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0)
return -1;
if(object_table_magic != OBJECT_TABLE_MAGIC) {
if(PIOS_FLASHFS_CleabObjectTableHeader() < 0)
return -1;
}
int32_t addr = OBJECT_TABLE_START;
struct objectHeader header;
numObjects = 0;
// Loop through header area while objects detect to count how many saved
while(addr < OBJECT_TABLE_END) {
// Read the instance data
if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0)
return -1;
// Counting number of valid headers
if(header.objMagic != OBJ_MAGIC)
break;
numObjects++;
addr += sizeof(header);
}
return 0;
}
/**
* @brief Erase the headers for all objects in the flash chip
* @return 0 if successful, -1 if not
*/
static int32_t PIOS_FLASHFS_CleabObjectTableHeader()
{
if(PIOS_Flash_W25X_EraseSector(OBJECT_TABLE_START) != 0)
return -1;
uint32_t object_table_magic = OBJECT_TABLE_MAGIC;
if (PIOS_Flash_W25X_WriteData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0)
return -1;
return 0;
}
/**
* @brief Get the address of an object
* @param obj UAVObjHandle for that object
* @parma instId Instance id for that object
* @return address if successful, -1 if not found
*/
static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
{
int32_t addr = OBJECT_TABLE_START;
struct objectHeader header;
// Loop through header area while objects detect to count how many saved
while(addr < OBJECT_TABLE_END) {
// Read the instance data
if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -1;
if(header.objMagic != OBJ_MAGIC)
break; // stop searching once hit first non-object header
else if (header.objId == objId && header.instId == instId)
break;
addr += sizeof(header);
}
if (header.objId == objId && header.instId == instId)
return header.address;
return -1;
}
/**
* @brief Returns an address for a new object and creates entry into object table
* @param[in] obj Object handle for object to be saved
* @param[in] instId The instance id of object to be saved
* @return 0 if success or error code
* @retval -1 Object not found
* @retval -2 No room in object table
* @retval -3 Unable to write entry into object table
* @retval -4 FS not initialized
*/
int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
{
struct objectHeader header;
if(numObjects < 0)
return -4;
// Don't worry about max size of flash chip here, other code will catch that
header.objMagic = OBJ_MAGIC;
header.objId = objId;
header.instId = instId;
header.address = OBJECT_TABLE_END + SECTOR_SIZE * numObjects;
int32_t addr = OBJECT_TABLE_START + sizeof(header) * numObjects;
// No room for this header in object table
if((addr + sizeof(header)) > OBJECT_TABLE_END)
return -2;
if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -3;
// This numObejcts value must stay consistent or there will be a break in the table
// and later the table will have bad values in it
numObjects++;
return header.address;
}
/**
* @brief Saves one object instance per sector
* @param[in] obj UAVObjHandle the object to save
* @param[in] instId The instance of the object to save
* @return 0 if success or -1 if failure
* @note This uses one sector on the flash chip per object so that no buffering in ram
* must be done when erasing the sector before a save
*/
int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data)
{
uint32_t objId = UAVObjGetID(obj);
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
// Object currently not saved
if(addr < 0)
addr = PIOS_FLASHFS_GetNewAddress(objId, instId);
// Could not allocate a sector
if(addr < 0)
return -1;
struct fileHeader header = {
.id = objId,
.instId = instId,
.size = UAVObjGetNumBytes(obj)
};
if(PIOS_Flash_W25X_EraseSector(addr) != 0)
return -2;
// Save header
// This information IS redundant with the object table id. Oh well. Better safe than sorry.
if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -3;
// Save data
if(PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0)
return -4;
return 0;
}
/**
* @brief Load one object instance per sector
* @param[in] obj UAVObjHandle the object to save
* @param[in] instId The instance of the object to save
* @return 0 if success or error code
* @retval -1 if object not in file table
* @retval -2 if unable to retrieve object header
* @retval -3 if loaded data instId or objId don't match
* @retval -4 if unable to retrieve instance data
* @note This uses one sector on the flash chip per object so that no buffering in ram
* must be done when erasing the sector before a save
*/
int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data)
{
uint32_t objId = UAVObjGetID(obj);
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
// Object currently not saved
if(addr < 0)
return -1;
struct fileHeader header;
// Load header
// This information IS redundant with the object table id. Oh well. Better safe than sorry.
if(PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -2;
if((header.id != objId) || (header.instId != instId))
return -3;
// Read the instance data
if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0)
return -4;
return 0;
}
/**
* @brief Delete object from flash
* @param[in] obj UAVObjHandle the object to save
* @param[in] instId The instance of the object to save
* @return 0 if success or error code
* @retval -1 if object not in file table
* @retval -2 Erase failed
* @note To avoid buffering the file table (1k ram!) the entry in the file table
* remains but destination sector is erased. This will make the load fail as the
* file header won't match the object. At next save it goes back there.
*/
int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId)
{
uint32_t objId = UAVObjGetID(obj);
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
// Object currently not saved
if(addr < 0)
return -1;
if(PIOS_Flash_W25X_EraseSector(addr) != 0)
return -2;
return 0;
}

View File

@ -0,0 +1,37 @@
/**
******************************************************************************
*
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_FLASHFS_OBJLIST Object list based flash filesystem (low ram)
* @{
*
* @file pios_flashfs_objlist.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief A file system for storing UAVObject in flash chip
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "openpilot.h"
#include "uavobjectmanager.h"
int32_t PIOS_FLASHFS_Init();
int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data);
int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data);
int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId);

View File

@ -1,135 +1,136 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file pios.h * @file pios.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main PiOS header. * @brief Main PiOS header.
* - Central header for the project. * - Central header for the project.
* @see The GNU Public License (GPL) Version 3 * @see The GNU Public License (GPL) Version 3
* *
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#ifndef PIOS_H #ifndef PIOS_H
#define PIOS_H #define PIOS_H
/* PIOS Feature Selection */ /* PIOS Feature Selection */
#include "pios_config.h" #include "pios_config.h"
#if defined(PIOS_INCLUDE_FREERTOS) #if defined(PIOS_INCLUDE_FREERTOS)
/* FreeRTOS Includes */ /* FreeRTOS Includes */
#include "FreeRTOS.h" #include "FreeRTOS.h"
#include "task.h" #include "task.h"
#include "queue.h" #include "queue.h"
#include "semphr.h" #include "semphr.h"
#endif #endif
/* C Lib Includes */ /* C Lib Includes */
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
#include <stdarg.h> #include <stdarg.h>
#include <string.h> #include <string.h>
#include <math.h> #include <math.h>
/* STM32 Std Perf Lib */ /* STM32 Std Perf Lib */
#include <stm32f10x.h> #include <stm32f10x.h>
#include <stm32f10x_conf.h> #include <stm32f10x_conf.h>
#if defined(PIOS_INCLUDE_SDCARD) #if defined(PIOS_INCLUDE_SDCARD)
/* Dosfs Includes */ /* Dosfs Includes */
#include <dosfs.h> #include <dosfs.h>
/* Mass Storage Device Includes */ /* Mass Storage Device Includes */
#include <msd.h> #include <msd.h>
#endif #endif
/* Generic initcall infrastructure */ /* Generic initcall infrastructure */
#include "pios_initcall.h" #include "pios_initcall.h"
/* PIOS Board Specific Device Configuration */ /* PIOS Board Specific Device Configuration */
#include "pios_board.h" #include "pios_board.h"
/* PIOS Hardware Includes (STM32F10x) */ /* PIOS Hardware Includes (STM32F10x) */
#include <pios_sys.h> #include <pios_sys.h>
#include <pios_delay.h> #include <pios_delay.h>
#include <pios_led.h> #include <pios_led.h>
#include <pios_sdcard.h> #include <pios_sdcard.h>
#include <pios_usart.h> #include <pios_usart.h>
#include <pios_irq.h> #include <pios_irq.h>
#include <pios_adc.h> #include <pios_adc.h>
#include <pios_servo.h> #include <pios_servo.h>
#include <pios_i2c.h> #include <pios_i2c.h>
#include <pios_spi.h> #include <pios_spi.h>
#include <pios_ppm.h> #include <pios_ppm.h>
#include <pios_pwm.h> #include <pios_pwm.h>
#include <pios_spektrum.h> #include <pios_spektrum.h>
#include <pios_usb_hid.h> #include <pios_usb_hid.h>
#include <pios_debug.h> #include <pios_debug.h>
#include <pios_gpio.h> #include <pios_gpio.h>
#if defined(PIOS_INCLUDE_EXTI) #if defined(PIOS_INCLUDE_EXTI)
#include <pios_exti.h> #include <pios_exti.h>
#endif #endif
#include <pios_wdg.h> #include <pios_wdg.h>
/* PIOS Hardware Includes (Common) */ /* PIOS Hardware Includes (Common) */
#include <pios_sdcard.h> #include <pios_sdcard.h>
#include <pios_com.h> #include <pios_com.h>
#if defined(PIOS_INCLUDE_BMP085) #if defined(PIOS_INCLUDE_BMP085)
#include <pios_bmp085.h> #include <pios_bmp085.h>
#endif #endif
#if defined(PIOS_INCLUDE_HCSR04) #if defined(PIOS_INCLUDE_HCSR04)
#include <pios_hcsr04.h> #include <pios_hcsr04.h>
#endif #endif
#if defined(PIOS_INCLUDE_HMC5843) #if defined(PIOS_INCLUDE_HMC5843)
#include <pios_hmc5843.h> #include <pios_hmc5843.h>
#endif #endif
#if defined(PIOS_INCLUDE_HMC5883) #if defined(PIOS_INCLUDE_HMC5883)
#include <pios_hmc5883.h> #include <pios_hmc5883.h>
#endif #endif
#if defined(PIOS_INCLUDE_I2C_ESC) #if defined(PIOS_INCLUDE_I2C_ESC)
#include <pios_i2c_esc.h> #include <pios_i2c_esc.h>
#endif #endif
#if defined(PIOS_INCLUDE_IMU3000) #if defined(PIOS_INCLUDE_IMU3000)
#include <pios_imu3000.h> #include <pios_imu3000.h>
#endif #endif
#include <pios_iap.h> #include <pios_iap.h>
#if defined(PIOS_INCLUDE_ADXL345) #if defined(PIOS_INCLUDE_ADXL345)
#include <pios_adxl345.h> #include <pios_adxl345.h>
#endif #endif
#if defined(PIOS_INCLUDE_BMA180) #if defined(PIOS_INCLUDE_BMA180)
#include <pios_bma180.h> #include <pios_bma180.h>
#endif #endif
#if defined(PIOS_INCLUDE_FLASH) #if defined(PIOS_INCLUDE_FLASH)
#include <pios_flash_w25x.h> #include <pios_flash_w25x.h>
#endif #include <pios_flashfs_objlist.h>
#endif
#if defined(PIOS_INCLUDE_BL_HELPER)
#include <pios_bl_helper.h> #if defined(PIOS_INCLUDE_BL_HELPER)
#endif #include <pios_bl_helper.h>
#endif
#if defined(PIOS_INCLUDE_USB)
/* USB Libs */ #if defined(PIOS_INCLUDE_USB)
#include <usb_lib.h> /* USB Libs */
#endif #include <usb_lib.h>
#endif
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
#endif /* PIOS_H */
#endif /* PIOS_H */

View File

@ -3171,6 +3171,8 @@
65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; }; 65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = "<group>"; }; 65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = "<group>"; };
65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; }; 65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flashfs_objlist.c; sourceTree = "<group>"; };
65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flashfs_objlist.h; sourceTree = "<group>"; };
/* End PBXFileReference section */ /* End PBXFileReference section */
/* Begin PBXGroup section */ /* Begin PBXGroup section */
@ -7657,6 +7659,7 @@
65E8F03711EFF25C00BBF654 /* printf-stdarg.c */, 65E8F03711EFF25C00BBF654 /* printf-stdarg.c */,
6528CCB412E406B800CF5144 /* pios_adxl345.c */, 6528CCB412E406B800CF5144 /* pios_adxl345.c */,
6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */, 6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */,
65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */,
); );
name = Common; name = Common;
path = ../../PiOS/Common; path = ../../PiOS/Common;
@ -7681,6 +7684,7 @@
65E8F03E11EFF25C00BBF654 /* pios_debug.h */, 65E8F03E11EFF25C00BBF654 /* pios_debug.h */,
65E8F03F11EFF25C00BBF654 /* pios_delay.h */, 65E8F03F11EFF25C00BBF654 /* pios_delay.h */,
65E8F04011EFF25C00BBF654 /* pios_exti.h */, 65E8F04011EFF25C00BBF654 /* pios_exti.h */,
65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */,
65E8F04111EFF25C00BBF654 /* pios_gpio.h */, 65E8F04111EFF25C00BBF654 /* pios_gpio.h */,
65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */, 65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */,
65E8F04311EFF25C00BBF654 /* pios_i2c.h */, 65E8F04311EFF25C00BBF654 /* pios_i2c.h */,

View File

@ -1,1607 +1,1498 @@
/** /**
****************************************************************************** ******************************************************************************
* @addtogroup UAVObjects OpenPilot UAVObjects * @addtogroup UAVObjects OpenPilot UAVObjects
* @{ * @{
* @addtogroup UAV Object Manager * @addtogroup UAV Object Manager
* @brief The core UAV Objects functions, most of which are wrappered by * @brief The core UAV Objects functions, most of which are wrappered by
* autogenerated defines * autogenerated defines
* @{ * @{
* *
* *
* @file uavobjectmanager.h * @file uavobjectmanager.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Object manager library. This library holds a collection of all objects. * @brief Object manager library. This library holds a collection of all objects.
* It can be used by all modules/libraries to find an object reference. * It can be used by all modules/libraries to find an object reference.
* @see The GNU Public License (GPL) Version 3 * @see The GNU Public License (GPL) Version 3
* *
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "openpilot.h" #include "openpilot.h"
// Constants // Constants
// Private types // Private types
/** /**
* List of event queues and the eventmask associated with the queue. * List of event queues and the eventmask associated with the queue.
*/ */
struct ObjectEventListStruct { struct ObjectEventListStruct {
xQueueHandle queue; xQueueHandle queue;
UAVObjEventCallback cb; UAVObjEventCallback cb;
int32_t eventMask; int32_t eventMask;
struct ObjectEventListStruct* next; struct ObjectEventListStruct *next;
}; };
typedef struct ObjectEventListStruct ObjectEventList; typedef struct ObjectEventListStruct ObjectEventList;
/** /**
* List of object instances, holds the actual data structure and instance ID * List of object instances, holds the actual data structure and instance ID
*/ */
struct ObjectInstListStruct { struct ObjectInstListStruct {
void* data; void *data;
uint16_t instId; uint16_t instId;
struct ObjectInstListStruct* next; struct ObjectInstListStruct *next;
}; };
typedef struct ObjectInstListStruct ObjectInstList; typedef struct ObjectInstListStruct ObjectInstList;
/** /**
* List of objects registered in the object manager * List of objects registered in the object manager
*/ */
struct ObjectListStruct { struct ObjectListStruct {
uint32_t id; /** The object ID */ uint32_t id;
const char* name; /** The object name */ /** The object ID */
int8_t isMetaobject; /** Set to 1 if this is a metaobject */ const char *name;
int8_t isSingleInstance; /** Set to 1 if this object has a single instance */ /** The object name */
int8_t isSettings; /** Set to 1 if this object is a settings object */ int8_t isMetaobject;
uint16_t numBytes; /** Number of data bytes contained in the object (for a single instance) */ /** Set to 1 if this is a metaobject */
uint16_t numInstances; /** Number of instances */ int8_t isSingleInstance;
struct ObjectListStruct* linkedObj; /** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */ /** Set to 1 if this object has a single instance */
ObjectInstList instances; /** List of object instances, instance 0 always exists */ int8_t isSettings;
ObjectEventList* events; /** Event queues registered on the object */ /** Set to 1 if this object is a settings object */
struct ObjectListStruct* next; /** Needed by linked list library (utlist.h) */ uint16_t numBytes;
}; /** Number of data bytes contained in the object (for a single instance) */
typedef struct ObjectListStruct ObjectList; uint16_t numInstances;
/** Number of instances */
// Private functions struct ObjectListStruct *linkedObj;
static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event); /** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */
static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId); ObjectInstList instances;
static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId); /** List of object instances, instance 0 always exists */
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb, int32_t eventMask); ObjectEventList *events;
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb); /** Event queues registered on the object */
struct ObjectListStruct *next;
#if defined(PIOS_INCLUDE_SDCARD) /** Needed by linked list library (utlist.h) */
static void objectFilename(ObjectList* obj, uint8_t* filename); };
static void customSPrintf(uint8_t* buffer, uint8_t* format, ...); typedef struct ObjectListStruct ObjectList;
#endif
// Private functions
// Private variables static int32_t sendEvent(ObjectList * obj, uint16_t instId,
static ObjectList* objList; UAVObjEventType event);
static xSemaphoreHandle mutex; static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId);
static UAVObjMetadata defMetadata; static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId);
static UAVObjStats stats; static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
UAVObjEventCallback cb, int32_t eventMask);
/** static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
* Initialize the object manager UAVObjEventCallback cb);
* \return 0 Success
* \return -1 Failure #if defined(PIOS_INCLUDE_SDCARD)
*/ static void objectFilename(ObjectList * obj, uint8_t * filename);
int32_t UAVObjInitialize() static void customSPrintf(uint8_t * buffer, uint8_t * format, ...);
{ #endif
// Initialize variables
objList = NULL; // Private variables
memset(&stats, 0, sizeof(UAVObjStats)); static ObjectList *objList;
static xSemaphoreHandle mutex;
// Create mutex static UAVObjMetadata defMetadata;
mutex = xSemaphoreCreateRecursiveMutex(); static UAVObjStats stats;
if (mutex == NULL)
return -1; /**
* Initialize the object manager
// Initialize default metadata structure (metadata of metaobjects) * \return 0 Success
defMetadata.access = ACCESS_READWRITE; * \return -1 Failure
defMetadata.gcsAccess = ACCESS_READWRITE; */
defMetadata.telemetryAcked = 1; int32_t UAVObjInitialize()
defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE; {
defMetadata.telemetryUpdatePeriod = 0; // Initialize variables
defMetadata.gcsTelemetryAcked = 1; objList = NULL;
defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE; memset(&stats, 0, sizeof(UAVObjStats));
defMetadata.gcsTelemetryUpdatePeriod = 0;
defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE; // Create mutex
defMetadata.loggingUpdatePeriod = 0; mutex = xSemaphoreCreateRecursiveMutex();
if (mutex == NULL)
// Done return -1;
return 0;
} // Initialize default metadata structure (metadata of metaobjects)
defMetadata.access = ACCESS_READWRITE;
/** defMetadata.gcsAccess = ACCESS_READWRITE;
* Get the statistics counters defMetadata.telemetryAcked = 1;
* @param[out] statsOut The statistics counters will be copied there defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE;
*/ defMetadata.telemetryUpdatePeriod = 0;
void UAVObjGetStats(UAVObjStats* statsOut) defMetadata.gcsTelemetryAcked = 1;
{ defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); defMetadata.gcsTelemetryUpdatePeriod = 0;
memcpy(statsOut, &stats, sizeof(UAVObjStats)); defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE;
xSemaphoreGiveRecursive(mutex); defMetadata.loggingUpdatePeriod = 0;
}
// Done
/** return 0;
* Clear the statistics counters }
*/
void UAVObjClearStats() /**
{ * Get the statistics counters
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * @param[out] statsOut The statistics counters will be copied there
memset(&stats, 0, sizeof(UAVObjStats)); */
xSemaphoreGiveRecursive(mutex); void UAVObjGetStats(UAVObjStats * statsOut)
} {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
/** memcpy(statsOut, &stats, sizeof(UAVObjStats));
* Register and new object in the object manager. xSemaphoreGiveRecursive(mutex);
* \param[in] id Unique object ID }
* \param[in] name Object name
* \param[in] nameName Metaobject name /**
* \param[in] isMetaobject Is this a metaobject (1:true, 0:false) * Clear the statistics counters
* \param[in] isSingleInstance Is this a single instance or multi-instance object */
* \param[in] isSettings Is this a settings object void UAVObjClearStats()
* \param[in] numBytes Number of bytes of object data (for one instance) {
* \param[in] initCb Default field and metadata initialization function xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* \return Object handle, or NULL if failure. memset(&stats, 0, sizeof(UAVObjStats));
* \return xSemaphoreGiveRecursive(mutex);
*/ }
UAVObjHandle UAVObjRegister(uint32_t id, const char* name, const char* metaName, int32_t isMetaobject,
int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb) /**
{ * Register and new object in the object manager.
ObjectList* objEntry; * \param[in] id Unique object ID
ObjectInstList* instEntry; * \param[in] name Object name
ObjectList* metaObj; * \param[in] nameName Metaobject name
* \param[in] isMetaobject Is this a metaobject (1:true, 0:false)
// Get lock * \param[in] isSingleInstance Is this a single instance or multi-instance object
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * \param[in] isSettings Is this a settings object
* \param[in] numBytes Number of bytes of object data (for one instance)
// Check that the object is not already registered * \param[in] initCb Default field and metadata initialization function
LL_FOREACH(objList, objEntry) * \return Object handle, or NULL if failure.
{ * \return
if (objEntry->id == id) */
{ UAVObjHandle UAVObjRegister(uint32_t id, const char *name,
// Already registered, ignore const char *metaName, int32_t isMetaobject,
xSemaphoreGiveRecursive(mutex); int32_t isSingleInstance, int32_t isSettings,
return NULL; uint32_t numBytes,
} UAVObjInitializeCallback initCb)
} {
ObjectList *objEntry;
// Create and append entry ObjectInstList *instEntry;
objEntry = (ObjectList*)pvPortMalloc(sizeof(ObjectList)); ObjectList *metaObj;
if (objEntry == NULL)
{ // Get lock
xSemaphoreGiveRecursive(mutex); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
return NULL;
} // Check that the object is not already registered
objEntry->id = id; LL_FOREACH(objList, objEntry) {
objEntry->name = name; if (objEntry->id == id) {
objEntry->isMetaobject = (int8_t)isMetaobject; // Already registered, ignore
objEntry->isSingleInstance = (int8_t)isSingleInstance; xSemaphoreGiveRecursive(mutex);
objEntry->isSettings = (int8_t)isSettings; return NULL;
objEntry->numBytes = numBytes; }
objEntry->events = NULL; }
objEntry->numInstances = 0;
objEntry->instances.data = NULL; // Create and append entry
objEntry->instances.instId = 0xFFFF; objEntry = (ObjectList *) pvPortMalloc(sizeof(ObjectList));
objEntry->instances.next = NULL; if (objEntry == NULL) {
objEntry->linkedObj = NULL; // will be set later xSemaphoreGiveRecursive(mutex);
LL_APPEND(objList, objEntry); return NULL;
}
// Create instance zero objEntry->id = id;
instEntry = createInstance(objEntry, 0); objEntry->name = name;
if ( instEntry == NULL ) objEntry->isMetaobject = (int8_t) isMetaobject;
{ objEntry->isSingleInstance = (int8_t) isSingleInstance;
xSemaphoreGiveRecursive(mutex); objEntry->isSettings = (int8_t) isSettings;
return NULL; objEntry->numBytes = numBytes;
} objEntry->events = NULL;
objEntry->numInstances = 0;
// Create metaobject and update linkedObj objEntry->instances.data = NULL;
if (isMetaobject) objEntry->instances.instId = 0xFFFF;
{ objEntry->instances.next = NULL;
objEntry->linkedObj = NULL; // will be set later objEntry->linkedObj = NULL; // will be set later
} LL_APPEND(objList, objEntry);
else
{ // Create instance zero
// Create metaobject instEntry = createInstance(objEntry, 0);
metaObj = (ObjectList*)UAVObjRegister(id+1, metaName, NULL, 1, 1, 0, sizeof(UAVObjMetadata), NULL); if (instEntry == NULL) {
// Link two objects xSemaphoreGiveRecursive(mutex);
objEntry->linkedObj = metaObj; return NULL;
metaObj->linkedObj = objEntry; }
} // Create metaobject and update linkedObj
if (isMetaobject) {
// Initialize object fields and metadata to default values objEntry->linkedObj = NULL; // will be set later
if ( initCb != NULL ) } else {
{ // Create metaobject
initCb((UAVObjHandle)objEntry, 0); metaObj =
} (ObjectList *) UAVObjRegister(id + 1, metaName,
NULL, 1, 1, 0,
// Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object) sizeof
if ( !objEntry->isMetaobject ) (UAVObjMetadata),
{ NULL);
UAVObjLoad( (UAVObjHandle)objEntry->linkedObj, 0 ); // Link two objects
} objEntry->linkedObj = metaObj;
metaObj->linkedObj = objEntry;
// If this is a settings object, attempt to load from SD card }
if ( objEntry->isSettings )
{ // Initialize object fields and metadata to default values
UAVObjLoad( (UAVObjHandle)objEntry, 0 ); if (initCb != NULL) {
} initCb((UAVObjHandle) objEntry, 0);
}
// Release lock // Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object)
xSemaphoreGiveRecursive(mutex); if (!objEntry->isMetaobject) {
return (UAVObjHandle)objEntry; UAVObjLoad((UAVObjHandle) objEntry->linkedObj, 0);
} }
// If this is a settings object, attempt to load from SD card
/** if (objEntry->isSettings) {
* Retrieve an object from the list given its id UAVObjLoad((UAVObjHandle) objEntry, 0);
* \param[in] The object ID }
* \return The object or NULL if not found. // Release lock
*/ xSemaphoreGiveRecursive(mutex);
UAVObjHandle UAVObjGetByID(uint32_t id) return (UAVObjHandle) objEntry;
{ }
ObjectList* objEntry;
/**
// Get lock * Retrieve an object from the list given its id
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * \param[in] The object ID
* \return The object or NULL if not found.
// Look for object */
LL_FOREACH(objList, objEntry) UAVObjHandle UAVObjGetByID(uint32_t id)
{ {
if (objEntry->id == id) ObjectList *objEntry;
{
// Release lock // Get lock
xSemaphoreGiveRecursive(mutex); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Done, object found
return (UAVObjHandle)objEntry; // Look for object
} LL_FOREACH(objList, objEntry) {
} if (objEntry->id == id) {
// Release lock
// Object not found, release lock and return error xSemaphoreGiveRecursive(mutex);
xSemaphoreGiveRecursive(mutex); // Done, object found
return NULL; return (UAVObjHandle) objEntry;
} }
}
/**
* Retrieve an object from the list given its name // Object not found, release lock and return error
* \param[in] name The name of the object xSemaphoreGiveRecursive(mutex);
* \return The object or NULL if not found. return NULL;
*/ }
UAVObjHandle UAVObjGetByName(char* name)
{ /**
ObjectList* objEntry; * Retrieve an object from the list given its name
* \param[in] name The name of the object
// Get lock * \return The object or NULL if not found.
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); */
UAVObjHandle UAVObjGetByName(char *name)
// Look for object {
LL_FOREACH(objList, objEntry) ObjectList *objEntry;
{
if (objEntry->name != NULL && strcmp(objEntry->name, name) == 0) // Get lock
{ xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Release lock
xSemaphoreGiveRecursive(mutex); // Look for object
// Done, object found LL_FOREACH(objList, objEntry) {
return (UAVObjHandle)objEntry; if (objEntry->name != NULL
} && strcmp(objEntry->name, name) == 0) {
} // Release lock
xSemaphoreGiveRecursive(mutex);
// Object not found, release lock and return error // Done, object found
xSemaphoreGiveRecursive(mutex); return (UAVObjHandle) objEntry;
return NULL; }
} }
/** // Object not found, release lock and return error
* Get the object's ID xSemaphoreGiveRecursive(mutex);
* \param[in] obj The object handle return NULL;
* \return The object ID }
*/
uint32_t UAVObjGetID(UAVObjHandle obj) /**
{ * Get the object's ID
return ((ObjectList*)obj)->id; * \param[in] obj The object handle
} * \return The object ID
*/
/** uint32_t UAVObjGetID(UAVObjHandle obj)
* Get the object's name {
* \param[in] obj The object handle return ((ObjectList *) obj)->id;
* \return The object's name }
*/
const char* UAVObjGetName(UAVObjHandle obj) /**
{ * Get the object's name
return ((ObjectList*)obj)->name; * \param[in] obj The object handle
} * \return The object's name
*/
/** const char *UAVObjGetName(UAVObjHandle obj)
* Get the number of bytes of the object's data (for one instance) {
* \param[in] obj The object handle return ((ObjectList *) obj)->name;
* \return The number of bytes }
*/
uint32_t UAVObjGetNumBytes(UAVObjHandle obj) /**
{ * Get the number of bytes of the object's data (for one instance)
return ((ObjectList*)obj)->numBytes; * \param[in] obj The object handle
} * \return The number of bytes
*/
/** uint32_t UAVObjGetNumBytes(UAVObjHandle obj)
* Get the object this object is linked to. For regular objects, the linked object {
* is the metaobject. For metaobjects the linked object is the parent object. return ((ObjectList *) obj)->numBytes;
* This function is normally only needed by the telemetry module. }
* \param[in] obj The object handle
* \return The object linked object handle /**
*/ * Get the object this object is linked to. For regular objects, the linked object
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj) * is the metaobject. For metaobjects the linked object is the parent object.
{ * This function is normally only needed by the telemetry module.
return (UAVObjHandle)(((ObjectList*)obj)->linkedObj); * \param[in] obj The object handle
} * \return The object linked object handle
*/
/** UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj)
* Get the number of instances contained in the object. {
* \param[in] obj The object handle return (UAVObjHandle) (((ObjectList *) obj)->linkedObj);
* \return The number of instances }
*/
uint16_t UAVObjGetNumInstances(UAVObjHandle obj) /**
{ * Get the number of instances contained in the object.
uint32_t numInstances; * \param[in] obj The object handle
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * \return The number of instances
numInstances = ((ObjectList*)obj)->numInstances; */
xSemaphoreGiveRecursive(mutex); uint16_t UAVObjGetNumInstances(UAVObjHandle obj)
return numInstances; {
} uint32_t numInstances;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
/** numInstances = ((ObjectList *) obj)->numInstances;
* Create a new instance in the object. xSemaphoreGiveRecursive(mutex);
* \param[in] obj The object handle return numInstances;
* \return The instance ID or 0 if an error }
*/
uint16_t UAVObjCreateInstance(UAVObjHandle obj, UAVObjInitializeCallback initCb) /**
{ * Create a new instance in the object.
ObjectList* objEntry; * \param[in] obj The object handle
ObjectInstList* instEntry; * \return The instance ID or 0 if an error
*/
// Lock uint16_t UAVObjCreateInstance(UAVObjHandle obj,
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); UAVObjInitializeCallback initCb)
{
// Create new instance ObjectList *objEntry;
objEntry = (ObjectList*)obj; ObjectInstList *instEntry;
instEntry = createInstance(objEntry, objEntry->numInstances);
if ( instEntry == NULL ) // Lock
{ xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
xSemaphoreGiveRecursive(mutex);
return -1; // Create new instance
} objEntry = (ObjectList *) obj;
instEntry = createInstance(objEntry, objEntry->numInstances);
// Initialize instance data if (instEntry == NULL) {
if ( initCb != NULL ) xSemaphoreGiveRecursive(mutex);
{ return -1;
initCb(obj, instEntry->instId); }
} // Initialize instance data
if (initCb != NULL) {
// Unlock initCb(obj, instEntry->instId);
xSemaphoreGiveRecursive(mutex); }
return instEntry->instId; // Unlock
} xSemaphoreGiveRecursive(mutex);
return instEntry->instId;
/** }
* Does this object contains a single instance or multiple instances?
* \param[in] obj The object handle /**
* \return True (1) if this is a single instance object * Does this object contains a single instance or multiple instances?
*/ * \param[in] obj The object handle
int32_t UAVObjIsSingleInstance(UAVObjHandle obj) * \return True (1) if this is a single instance object
{ */
return ((ObjectList*)obj)->isSingleInstance; int32_t UAVObjIsSingleInstance(UAVObjHandle obj)
} {
return ((ObjectList *) obj)->isSingleInstance;
/** }
* Is this a metaobject?
* \param[in] obj The object handle /**
* \return True (1) if this is metaobject * Is this a metaobject?
*/ * \param[in] obj The object handle
int32_t UAVObjIsMetaobject(UAVObjHandle obj) * \return True (1) if this is metaobject
{ */
return ((ObjectList*)obj)->isMetaobject; int32_t UAVObjIsMetaobject(UAVObjHandle obj)
} {
return ((ObjectList *) obj)->isMetaobject;
/** }
* Is this a settings object?
* \param[in] obj The object handle /**
* \return True (1) if this is a settings object * Is this a settings object?
*/ * \param[in] obj The object handle
int32_t UAVObjIsSettings(UAVObjHandle obj) * \return True (1) if this is a settings object
{ */
return ((ObjectList*)obj)->isSettings; int32_t UAVObjIsSettings(UAVObjHandle obj)
} {
return ((ObjectList *) obj)->isSettings;
/** }
* Unpack an object from a byte array
* \param[in] obj The object handle /**
* \param[in] instId The instance ID * Unpack an object from a byte array
* \param[in] dataIn The byte array * \param[in] obj The object handle
* \return 0 if success or -1 if failure * \param[in] instId The instance ID
*/ * \param[in] dataIn The byte array
int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId, const uint8_t* dataIn) * \return 0 if success or -1 if failure
{ */
ObjectList* objEntry; int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId,
ObjectInstList* instEntry; const uint8_t * dataIn)
{
// Lock ObjectList *objEntry;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); ObjectInstList *instEntry;
// Cast handle to object // Lock
objEntry = (ObjectList*)obj; xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Get the instance // Cast handle to object
instEntry = getInstance(objEntry, instId); objEntry = (ObjectList *) obj;
// If the instance does not exist create it and any other instances before it // Get the instance
if ( instEntry == NULL ) instEntry = getInstance(objEntry, instId);
{
instEntry = createInstance(objEntry, instId); // If the instance does not exist create it and any other instances before it
if ( instEntry == NULL ) if (instEntry == NULL) {
{ instEntry = createInstance(objEntry, instId);
// Error, unlock and return if (instEntry == NULL) {
xSemaphoreGiveRecursive(mutex); // Error, unlock and return
return -1; xSemaphoreGiveRecursive(mutex);
} return -1;
} }
}
// Set the data // Set the data
memcpy(instEntry->data, dataIn, objEntry->numBytes); memcpy(instEntry->data, dataIn, objEntry->numBytes);
// Fire event // Fire event
sendEvent(objEntry, instId, EV_UNPACKED); sendEvent(objEntry, instId, EV_UNPACKED);
// Unlock // Unlock
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mutex);
return 0; return 0;
} }
/** /**
* Pack an object to a byte array * Pack an object to a byte array
* \param[in] obj The object handle * \param[in] obj The object handle
* \param[in] instId The instance ID * \param[in] instId The instance ID
* \param[out] dataOut The byte array * \param[out] dataOut The byte array
* \return 0 if success or -1 if failure * \return 0 if success or -1 if failure
*/ */
int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t* dataOut) int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t * dataOut)
{ {
ObjectList* objEntry; ObjectList *objEntry;
ObjectInstList* instEntry; ObjectInstList *instEntry;
// Lock // Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast handle to object // Cast handle to object
objEntry = (ObjectList*)obj; objEntry = (ObjectList *) obj;
// Get the instance // Get the instance
instEntry = getInstance(objEntry, instId); instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL ) if (instEntry == NULL) {
{ // Error, unlock and return
// Error, unlock and return xSemaphoreGiveRecursive(mutex);
xSemaphoreGiveRecursive(mutex); return -1;
return -1; }
} // Pack data
memcpy(dataOut, instEntry->data, objEntry->numBytes);
// Pack data
memcpy(dataOut, instEntry->data, objEntry->numBytes); // Unlock
xSemaphoreGiveRecursive(mutex);
// Unlock return 0;
xSemaphoreGiveRecursive(mutex); }
return 0;
} /**
* Save the data of the specified object instance to the file system (SD card).
/** * The object will be appended and the file will not be closed.
* Save the data of the specified object instance to the file system (SD card). * The object data can be restored using the UAVObjLoad function.
* The object will be appended and the file will not be closed. * @param[in] obj The object handle.
* The object data can be restored using the UAVObjLoad function. * @param[in] instId The instance ID
* @param[in] obj The object handle. * @param[in] file File to append to
* @param[in] instId The instance ID * @return 0 if success or -1 if failure
* @param[in] file File to append to */
* @return 0 if success or -1 if failure int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId,
*/ FILEINFO * file)
int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, FILEINFO* file) {
{ #if defined(PIOS_INCLUDE_SDCARD)
#if defined(PIOS_INCLUDE_SDCARD) uint32_t bytesWritten;
uint32_t bytesWritten; ObjectList *objEntry;
ObjectList* objEntry; ObjectInstList *instEntry;
ObjectInstList* instEntry;
// Check for file system availability
// Check for file system availability if (PIOS_SDCARD_IsMounted() == 0) {
if ( PIOS_SDCARD_IsMounted() == 0 ) return -1;
{ }
return -1; // Lock
} xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Lock // Cast to object
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); objEntry = (ObjectList *) obj;
// Cast to object // Get the instance information
objEntry = (ObjectList*)obj; instEntry = getInstance(objEntry, instId);
if (instEntry == NULL) {
// Get the instance information xSemaphoreGiveRecursive(mutex);
instEntry = getInstance(objEntry, instId); return -1;
if ( instEntry == NULL ) }
{ // Write the object ID
xSemaphoreGiveRecursive(mutex); PIOS_FWRITE(file, &objEntry->id, sizeof(objEntry->id),
return -1; &bytesWritten);
}
// Write the instance ID
// Write the object ID if (!objEntry->isSingleInstance) {
PIOS_FWRITE(file,&objEntry->id,sizeof(objEntry->id),&bytesWritten); PIOS_FWRITE(file, &instEntry->instId,
sizeof(instEntry->instId), &bytesWritten);
// Write the instance ID }
if (!objEntry->isSingleInstance) // Write the data and check that the write was successful
{ PIOS_FWRITE(file, instEntry->data, objEntry->numBytes,
PIOS_FWRITE(file,&instEntry->instId,sizeof(instEntry->instId),&bytesWritten); &bytesWritten);
} if (bytesWritten != objEntry->numBytes) {
xSemaphoreGiveRecursive(mutex);
// Write the data and check that the write was successful return -1;
PIOS_FWRITE(file,instEntry->data,objEntry->numBytes,&bytesWritten); }
if ( bytesWritten != objEntry->numBytes ) // Done
{ xSemaphoreGiveRecursive(mutex);
xSemaphoreGiveRecursive(mutex); #endif /* PIOS_INCLUDE_SDCARD */
return -1; return 0;
} }
// Done /**
xSemaphoreGiveRecursive(mutex); * Save the data of the specified object to the file system (SD card).
#endif /* PIOS_INCLUDE_SDCARD */ * If the object contains multiple instances, all of them will be saved.
return 0; * A new file with the name of the object will be created.
} * The object data can be restored using the UAVObjLoad function.
* @param[in] obj The object handle.
struct fileHeader { * @param[in] instId The instance ID
uint32_t id; * @param[in] file File to append to
uint16_t instId; * @return 0 if success or -1 if failure
uint16_t size; */
} __attribute__((packed)); int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId)
{
#define FLASH_MASK 0x001ff000 /* Select a sector */ #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList *objEntry = (ObjectList *) obj;
/**
* Save the data of the specified object to the file system (SD card). if (objEntry == NULL)
* If the object contains multiple instances, all of them will be saved. return -1;
* A new file with the name of the object will be created.
* The object data can be restored using the UAVObjLoad function. ObjectInstList *instEntry = getInstance(objEntry, instId);
* @param[in] obj The object handle.
* @param[in] instId The instance ID if (instEntry == NULL)
* @param[in] file File to append to return -1;
* @return 0 if success or -1 if failure
*/ if (instEntry->data == NULL)
int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId) return -1;
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) if (PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0)
ObjectList* objEntry = (ObjectList*)obj; return -1;
#endif
if(objEntry == NULL) #if defined(PIOS_INCLUDE_SDCARD)
return -1; FILEINFO file;
ObjectList *objEntry;
ObjectInstList* instEntry = getInstance(objEntry, instId); uint8_t filename[14];
if(instEntry == NULL) // Check for file system availability
return -1; if (PIOS_SDCARD_IsMounted() == 0) {
return -1;
if(instEntry->data == NULL) }
return -1; // Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
struct fileHeader header = { // Cast to object
.id = objEntry->id, objEntry = (ObjectList *) obj;
.instId = instId,
.size = objEntry->numBytes // Get filename
}; objectFilename(objEntry, filename);
uint32_t addr = (objEntry->id & FLASH_MASK); // Open file
PIOS_Flash_W25X_EraseSector(addr); if (PIOS_FOPEN_WRITE(filename, file)) {
PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)); xSemaphoreGiveRecursive(mutex);
PIOS_Flash_W25X_WriteData(addr + sizeof(header), instEntry->data,objEntry->numBytes); return -1;
#endif }
#if defined(PIOS_INCLUDE_SDCARD) // Append object
FILEINFO file; if (UAVObjSaveToFile(obj, instId, &file) == -1) {
ObjectList* objEntry; PIOS_FCLOSE(file);
uint8_t filename[14]; xSemaphoreGiveRecursive(mutex);
return -1;
// Check for file system availability }
if ( PIOS_SDCARD_IsMounted() == 0 ) // Done, close file and unlock
{ PIOS_FCLOSE(file);
return -1; xSemaphoreGiveRecursive(mutex);
} #endif /* PIOS_INCLUDE_SDCARD */
return 0;
// Lock }
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
/**
// Cast to object * Load an object from the file system (SD card).
objEntry = (ObjectList*)obj; * @param[in] file File to read from
* @return The handle of the object loaded or NULL if a failure
// Get filename */
objectFilename(objEntry, filename); UAVObjHandle UAVObjLoadFromFile(FILEINFO * file)
{
// Open file #if defined(PIOS_INCLUDE_SDCARD)
if ( PIOS_FOPEN_WRITE(filename,file) ) uint32_t bytesRead;
{ ObjectList *objEntry;
xSemaphoreGiveRecursive(mutex); ObjectInstList *instEntry;
return -1; uint32_t objId;
} uint16_t instId;
UAVObjHandle obj;
// Append object
if ( UAVObjSaveToFile(obj, instId, &file) == -1 ) // Check for file system availability
{ if (PIOS_SDCARD_IsMounted() == 0) {
PIOS_FCLOSE(file); return NULL;
xSemaphoreGiveRecursive(mutex); }
return -1; // Lock
} xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Done, close file and unlock // Read the object ID
PIOS_FCLOSE(file); if (PIOS_FREAD(file, &objId, sizeof(objId), &bytesRead)) {
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */ return NULL;
return 0; }
} // Get the object
obj = UAVObjGetByID(objId);
/** if (obj == 0) {
* Load an object from the file system (SD card). xSemaphoreGiveRecursive(mutex);
* @param[in] file File to read from return NULL;
* @return The handle of the object loaded or NULL if a failure }
*/ objEntry = (ObjectList *) obj;
UAVObjHandle UAVObjLoadFromFile(FILEINFO* file)
{ // Get the instance ID
#if defined(PIOS_INCLUDE_SDCARD) instId = 0;
uint32_t bytesRead; if (!objEntry->isSingleInstance) {
ObjectList* objEntry; if (PIOS_FREAD
ObjectInstList* instEntry; (file, &instId, sizeof(instId), &bytesRead)) {
uint32_t objId; xSemaphoreGiveRecursive(mutex);
uint16_t instId; return NULL;
UAVObjHandle obj; }
}
// Check for file system availability // Get the instance information
if ( PIOS_SDCARD_IsMounted() == 0 ) instEntry = getInstance(objEntry, instId);
{
return NULL; // If the instance does not exist create it and any other instances before it
} if (instEntry == NULL) {
instEntry = createInstance(objEntry, instId);
// Lock if (instEntry == NULL) {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); // Error, unlock and return
xSemaphoreGiveRecursive(mutex);
// Read the object ID return NULL;
if ( PIOS_FREAD(file,&objId,sizeof(objId),&bytesRead) ) }
{ }
xSemaphoreGiveRecursive(mutex); // Read the instance data
return NULL; if (PIOS_FREAD
} (file, instEntry->data, objEntry->numBytes, &bytesRead)) {
xSemaphoreGiveRecursive(mutex);
// Get the object return NULL;
obj = UAVObjGetByID(objId); }
if ( obj == 0 ) // Fire event
{ sendEvent(objEntry, instId, EV_UNPACKED);
xSemaphoreGiveRecursive(mutex);
return NULL; // Unlock
} xSemaphoreGiveRecursive(mutex);
objEntry = (ObjectList*)obj; return obj;
#else /* PIOS_INCLUDE_SDCARD */
// Get the instance ID return NULL;
instId = 0; #endif
if ( !objEntry->isSingleInstance ) }
{
if ( PIOS_FREAD(file,&instId,sizeof(instId),&bytesRead) ) /**
{ * Load an object from the file system (SD card).
xSemaphoreGiveRecursive(mutex); * A file with the name of the object will be opened.
return NULL; * The object data can be saved using the UAVObjSave function.
} * @param[in] obj The object handle.
} * @param[in] instId The object instance
* @return 0 if success or -1 if failure
// Get the instance information */
instEntry = getInstance(objEntry, instId); int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
{
// If the instance does not exist create it and any other instances before it #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
if ( instEntry == NULL ) ObjectList *objEntry = (ObjectList *) obj;
{
instEntry = createInstance(objEntry, instId); if (objEntry == NULL)
if ( instEntry == NULL ) return -1;
{
// Error, unlock and return ObjectInstList *instEntry = getInstance(objEntry, instId);
xSemaphoreGiveRecursive(mutex);
return NULL; if (instEntry == NULL)
} return -1;
}
if (instEntry->data == NULL)
// Read the instance data return -1;
if ( PIOS_FREAD(file,instEntry->data,objEntry->numBytes,&bytesRead) )
{ // Fire event on success
xSemaphoreGiveRecursive(mutex); if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0)
return NULL; sendEvent(objEntry, instId, EV_UNPACKED);
} else
return -1;
// Fire event #endif
sendEvent(objEntry, instId, EV_UNPACKED);
#if defined(PIOS_INCLUDE_SDCARD)
// Unlock FILEINFO file;
xSemaphoreGiveRecursive(mutex); ObjectList *objEntry;
return obj; UAVObjHandle loadedObj;
#else /* PIOS_INCLUDE_SDCARD */ ObjectList *loadedObjEntry;
return NULL; uint8_t filename[14];
#endif
} // Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
/** return -1;
* Load an object from the file system (SD card). }
* A file with the name of the object will be opened. // Lock
* The object data can be saved using the UAVObjSave function. xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* @param[in] obj The object handle.
* @param[in] instId The object instance // Cast to object
* @return 0 if success or -1 if failure objEntry = (ObjectList *) obj;
*/
int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) // Get filename
{ objectFilename(objEntry, filename);
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList* objEntry = (ObjectList*)obj; // Open file
if (PIOS_FOPEN_READ(filename, file)) {
if(objEntry == NULL) xSemaphoreGiveRecursive(mutex);
return -1; return -1;
}
ObjectInstList* instEntry = getInstance(objEntry, instId); // Load object
loadedObj = UAVObjLoadFromFile(&file);
if(instEntry == NULL) if (loadedObj == 0) {
return -1; PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
if(instEntry->data == NULL) return -1;
return -1; }
// Check that the IDs match
struct fileHeader header; loadedObjEntry = (ObjectList *) loadedObj;
uint32_t addr = (objEntry->id & FLASH_MASK); if (loadedObjEntry->id != objEntry->id) {
PIOS_FCLOSE(file);
PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)); xSemaphoreGiveRecursive(mutex);
return -1;
if(header.id != objEntry->id) }
return -1; // Done, close file and unlock
PIOS_FCLOSE(file);
// Read the instance data xSemaphoreGiveRecursive(mutex);
if (PIOS_Flash_W25X_ReadData(addr + sizeof(header) ,instEntry->data, objEntry->numBytes) != 0) #endif /* PIOS_INCLUDE_SDCARD */
return -1; return 0;
}
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED); /**
#endif * Delete an object from the file system (SD card).
* @param[in] obj The object handle.
#if defined(PIOS_INCLUDE_SDCARD) * @param[in] instId The object instance
FILEINFO file; * @return 0 if success or -1 if failure
ObjectList* objEntry; */
UAVObjHandle loadedObj; int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId)
ObjectList* loadedObjEntry; {
uint8_t filename[14]; #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
PIOS_FLASHFS_ObjDelete(obj, instId);
// Check for file system availability #endif
if ( PIOS_SDCARD_IsMounted() == 0 ) #if defined(PIOS_INCLUDE_SDCARD)
{ ObjectList *objEntry;
return -1; uint8_t filename[14];
}
// Check for file system availability
// Lock if (PIOS_SDCARD_IsMounted() == 0) {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); return -1;
}
// Cast to object // Lock
objEntry = (ObjectList*)obj; xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Get filename // Cast to object
objectFilename(objEntry, filename); objEntry = (ObjectList *) obj;
// Open file // Get filename
if ( PIOS_FOPEN_READ(filename,file) ) objectFilename(objEntry, filename);
{
xSemaphoreGiveRecursive(mutex); // Delete file
return -1; PIOS_FUNLINK(filename);
}
// Done
// Load object xSemaphoreGiveRecursive(mutex);
loadedObj = UAVObjLoadFromFile(&file); #endif /* PIOS_INCLUDE_SDCARD */
if (loadedObj == 0) return 0;
{ }
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex); /**
return -1; * Save all settings objects to the SD card.
} * @return 0 if success or -1 if failure
*/
// Check that the IDs match int32_t UAVObjSaveSettings()
loadedObjEntry = (ObjectList*)loadedObj; {
if ( loadedObjEntry->id != objEntry->id ) ObjectList *objEntry;
{
PIOS_FCLOSE(file); // Get lock
xSemaphoreGiveRecursive(mutex); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
return -1;
} // Save all settings objects
LL_FOREACH(objList, objEntry) {
// Done, close file and unlock // Check if this is a settings object
PIOS_FCLOSE(file); if (objEntry->isSettings) {
xSemaphoreGiveRecursive(mutex); // Save object
#endif /* PIOS_INCLUDE_SDCARD */ if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
return 0; -1) {
} xSemaphoreGiveRecursive(mutex);
return -1;
/** }
* Delete an object from the file system (SD card). }
* @param[in] obj The object handle. }
* @param[in] instId The object instance
* @return 0 if success or -1 if failure // Done
*/ xSemaphoreGiveRecursive(mutex);
int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId) return 0;
{ }
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList* objEntry = (ObjectList*)obj; /**
* Load all settings objects from the SD card.
if(objEntry == NULL) * @return 0 if success or -1 if failure
return -1; */
int32_t UAVObjLoadSettings()
uint32_t addr = (objEntry->id & FLASH_MASK); {
PIOS_Flash_W25X_EraseSector(addr); ObjectList *objEntry;
#endif
#if defined(PIOS_INCLUDE_SDCARD) // Get lock
ObjectList* objEntry; xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
uint8_t filename[14];
// Load all settings objects
// Check for file system availability LL_FOREACH(objList, objEntry) {
if ( PIOS_SDCARD_IsMounted() == 0 ) // Check if this is a settings object
{ if (objEntry->isSettings) {
return -1; // Load object
} if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
-1) {
// Lock xSemaphoreGiveRecursive(mutex);
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); return -1;
}
// Cast to object }
objEntry = (ObjectList*)obj; }
// Get filename // Done
objectFilename(objEntry, filename); xSemaphoreGiveRecursive(mutex);
return 0;
// Delete file }
PIOS_FUNLINK(filename);
/**
// Done * Delete all settings objects from the SD card.
xSemaphoreGiveRecursive(mutex); * @return 0 if success or -1 if failure
#endif /* PIOS_INCLUDE_SDCARD */ */
return 0; int32_t UAVObjDeleteSettings()
} {
ObjectList *objEntry;
/**
* Save all settings objects to the SD card. // Get lock
* @return 0 if success or -1 if failure xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
*/
int32_t UAVObjSaveSettings() // Save all settings objects
{ LL_FOREACH(objList, objEntry) {
ObjectList* objEntry; // Check if this is a settings object
if (objEntry->isSettings) {
// Get lock // Save object
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); if (UAVObjDelete((UAVObjHandle) objEntry, 0)
== -1) {
// Save all settings objects xSemaphoreGiveRecursive(mutex);
LL_FOREACH(objList, objEntry) return -1;
{ }
// Check if this is a settings object }
if ( objEntry->isSettings ) }
{
// Save object // Done
if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 ) xSemaphoreGiveRecursive(mutex);
{ return 0;
xSemaphoreGiveRecursive(mutex); }
return -1;
} /**
} * Save all metaobjects to the SD card.
} * @return 0 if success or -1 if failure
*/
// Done int32_t UAVObjSaveMetaobjects()
xSemaphoreGiveRecursive(mutex); {
return 0; ObjectList *objEntry;
}
// Get lock
/** xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* Load all settings objects from the SD card.
* @return 0 if success or -1 if failure // Save all settings objects
*/ LL_FOREACH(objList, objEntry) {
int32_t UAVObjLoadSettings() // Check if this is a settings object
{ if (objEntry->isMetaobject) {
ObjectList* objEntry; // Save object
if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
// Get lock -1) {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); xSemaphoreGiveRecursive(mutex);
return -1;
// Load all settings objects }
LL_FOREACH(objList, objEntry) }
{ }
// Check if this is a settings object
if ( objEntry->isSettings ) // Done
{ xSemaphoreGiveRecursive(mutex);
// Load object return 0;
if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 ) }
{
xSemaphoreGiveRecursive(mutex); /**
return -1; * Load all metaobjects from the SD card.
} * @return 0 if success or -1 if failure
} */
} int32_t UAVObjLoadMetaobjects()
{
// Done ObjectList *objEntry;
xSemaphoreGiveRecursive(mutex);
return 0; // Get lock
} xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
/** // Load all settings objects
* Delete all settings objects from the SD card. LL_FOREACH(objList, objEntry) {
* @return 0 if success or -1 if failure // Check if this is a settings object
*/ if (objEntry->isMetaobject) {
int32_t UAVObjDeleteSettings() // Load object
{ if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
ObjectList* objEntry; -1) {
xSemaphoreGiveRecursive(mutex);
// Get lock return -1;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); }
}
// Save all settings objects }
LL_FOREACH(objList, objEntry)
{ // Done
// Check if this is a settings object xSemaphoreGiveRecursive(mutex);
if ( objEntry->isSettings ) return 0;
{ }
// Save object
if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 ) /**
{ * Delete all metaobjects from the SD card.
xSemaphoreGiveRecursive(mutex); * @return 0 if success or -1 if failure
return -1; */
} int32_t UAVObjDeleteMetaobjects()
} {
} ObjectList *objEntry;
// Done // Get lock
xSemaphoreGiveRecursive(mutex); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
return 0;
} // Load all settings objects
LL_FOREACH(objList, objEntry) {
/** // Check if this is a settings object
* Save all metaobjects to the SD card. if (objEntry->isMetaobject) {
* @return 0 if success or -1 if failure // Load object
*/ if (UAVObjDelete((UAVObjHandle) objEntry, 0)
int32_t UAVObjSaveMetaobjects() == -1) {
{ xSemaphoreGiveRecursive(mutex);
ObjectList* objEntry; return -1;
}
// Get lock }
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); }
// Save all settings objects // Done
LL_FOREACH(objList, objEntry) xSemaphoreGiveRecursive(mutex);
{ return 0;
// Check if this is a settings object }
if ( objEntry->isMetaobject )
{ /**
// Save object * Set the object data
if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 ) * \param[in] obj The object handle
{ * \param[in] dataIn The object's data structure
xSemaphoreGiveRecursive(mutex); * \return 0 if success or -1 if failure
return -1; */
} int32_t UAVObjSetData(UAVObjHandle obj, const void *dataIn)
} {
} return UAVObjSetInstanceData(obj, 0, dataIn);
}
// Done
xSemaphoreGiveRecursive(mutex); /**
return 0; * Get the object data
} * \param[in] obj The object handle
* \param[out] dataOut The object's data structure
/** * \return 0 if success or -1 if failure
* Load all metaobjects from the SD card. */
* @return 0 if success or -1 if failure int32_t UAVObjGetData(UAVObjHandle obj, void *dataOut)
*/ {
int32_t UAVObjLoadMetaobjects() return UAVObjGetInstanceData(obj, 0, dataOut);
{ }
ObjectList* objEntry;
/**
// Get lock * Set the data of a specific object instance
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * \param[in] obj The object handle
* \param[in] instId The object instance ID
// Load all settings objects * \param[in] dataIn The object's data structure
LL_FOREACH(objList, objEntry) * \return 0 if success or -1 if failure
{ */
// Check if this is a settings object int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId,
if ( objEntry->isMetaobject ) const void *dataIn)
{ {
// Load object ObjectList *objEntry;
if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 ) ObjectInstList *instEntry;
{ UAVObjMetadata *mdata;
xSemaphoreGiveRecursive(mutex);
return -1; // Lock
} xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
}
} // Cast to object info
objEntry = (ObjectList *) obj;
// Done
xSemaphoreGiveRecursive(mutex); // Check access level
return 0; if (!objEntry->isMetaobject) {
} mdata =
(UAVObjMetadata *) (objEntry->linkedObj->instances.
/** data);
* Delete all metaobjects from the SD card. if (mdata->access == ACCESS_READONLY) {
* @return 0 if success or -1 if failure xSemaphoreGiveRecursive(mutex);
*/ return -1;
int32_t UAVObjDeleteMetaobjects() }
{ }
ObjectList* objEntry; // Get instance information
instEntry = getInstance(objEntry, instId);
// Get lock if (instEntry == NULL) {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); // Error, unlock and return
xSemaphoreGiveRecursive(mutex);
// Load all settings objects return -1;
LL_FOREACH(objList, objEntry) }
{ // Set data
// Check if this is a settings object memcpy(instEntry->data, dataIn, objEntry->numBytes);
if ( objEntry->isMetaobject )
{ // Fire event
// Load object sendEvent(objEntry, instId, EV_UPDATED);
if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 )
{ // Unlock
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mutex);
return -1; return 0;
} }
}
} /**
* Get the data of a specific object instance
// Done * \param[in] obj The object handle
xSemaphoreGiveRecursive(mutex); * \param[in] instId The object instance ID
return 0; * \param[out] dataOut The object's data structure
} * \return 0 if success or -1 if failure
*/
/** int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId,
* Set the object data void *dataOut)
* \param[in] obj The object handle {
* \param[in] dataIn The object's data structure ObjectList *objEntry;
* \return 0 if success or -1 if failure ObjectInstList *instEntry;
*/
int32_t UAVObjSetData(UAVObjHandle obj, const void* dataIn) // Lock
{ xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
return UAVObjSetInstanceData(obj, 0, dataIn);
} // Cast to object info
objEntry = (ObjectList *) obj;
/**
* Get the object data // Get instance information
* \param[in] obj The object handle instEntry = getInstance(objEntry, instId);
* \param[out] dataOut The object's data structure if (instEntry == NULL) {
* \return 0 if success or -1 if failure // Error, unlock and return
*/ xSemaphoreGiveRecursive(mutex);
int32_t UAVObjGetData(UAVObjHandle obj, void* dataOut) return -1;
{ }
return UAVObjGetInstanceData(obj, 0, dataOut); // Set data
} memcpy(dataOut, instEntry->data, objEntry->numBytes);
/** // Unlock
* Set the data of a specific object instance xSemaphoreGiveRecursive(mutex);
* \param[in] obj The object handle return 0;
* \param[in] instId The object instance ID }
* \param[in] dataIn The object's data structure
* \return 0 if success or -1 if failure /**
*/ * Set the object metadata
int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, const void* dataIn) * \param[in] obj The object handle
{ * \param[in] dataIn The object's metadata structure
ObjectList* objEntry; * \return 0 if success or -1 if failure
ObjectInstList* instEntry; */
UAVObjMetadata* mdata; int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn)
{
// Lock ObjectList *objEntry;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Lock
// Cast to object info xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
objEntry = (ObjectList*)obj;
// Set metadata (metadata of metaobjects can not be modified)
// Check access level objEntry = (ObjectList *) obj;
if ( !objEntry->isMetaobject ) if (!objEntry->isMetaobject) {
{ UAVObjSetData((UAVObjHandle) objEntry->linkedObj,
mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data); dataIn);
if ( mdata->access == ACCESS_READONLY ) } else {
{ return -1;
xSemaphoreGiveRecursive(mutex); }
return -1;
} // Unlock
} xSemaphoreGiveRecursive(mutex);
return 0;
// Get instance information }
instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL ) /**
{ * Get the object metadata
// Error, unlock and return * \param[in] obj The object handle
xSemaphoreGiveRecursive(mutex); * \param[out] dataOut The object's metadata structure
return -1; * \return 0 if success or -1 if failure
} */
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut)
// Set data {
memcpy(instEntry->data, dataIn, objEntry->numBytes); ObjectList *objEntry;
// Fire event // Lock
sendEvent(objEntry, instId, EV_UPDATED); xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Unlock // Get metadata
xSemaphoreGiveRecursive(mutex); objEntry = (ObjectList *) obj;
return 0; if (objEntry->isMetaobject) {
} memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata));
} else {
/** UAVObjGetData((UAVObjHandle) objEntry->linkedObj,
* Get the data of a specific object instance dataOut);
* \param[in] obj The object handle }
* \param[in] instId The object instance ID
* \param[out] dataOut The object's data structure // Unlock
* \return 0 if success or -1 if failure xSemaphoreGiveRecursive(mutex);
*/ return 0;
int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, void* dataOut) }
{
ObjectList* objEntry; /**
ObjectInstList* instEntry; * Check if an object is read only
* \param[in] obj The object handle
// Lock * \return
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); * \arg 0 if not read only
* \arg 1 if read only
// Cast to object info * \arg -1 if unable to get meta data
objEntry = (ObjectList*)obj; */
int8_t UAVObjReadOnly(UAVObjHandle obj)
// Get instance information {
instEntry = getInstance(objEntry, instId); ObjectList *objEntry;
if ( instEntry == NULL ) UAVObjMetadata *mdata;
{
// Error, unlock and return // Cast to object info
xSemaphoreGiveRecursive(mutex); objEntry = (ObjectList *) obj;
return -1;
} // Check access level
if (!objEntry->isMetaobject) {
// Set data mdata =
memcpy(dataOut, instEntry->data, objEntry->numBytes); (UAVObjMetadata *) (objEntry->linkedObj->instances.
data);
// Unlock return mdata->access == ACCESS_READONLY;
xSemaphoreGiveRecursive(mutex); }
return 0; return -1;
} }
/** /**
* Set the object metadata * Connect an event queue to the object, if the queue is already connected then the event mask is only updated.
* \param[in] obj The object handle * All events matching the event mask will be pushed to the event queue.
* \param[in] dataIn The object's metadata structure * \param[in] obj The object handle
* \return 0 if success or -1 if failure * \param[in] queue The event queue
*/ * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata* dataIn) * \return 0 if success or -1 if failure
{ */
ObjectList* objEntry; int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue,
int32_t eventMask)
// Lock {
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Set metadata (metadata of metaobjects can not be modified) res = connectObj(obj, queue, 0, eventMask);
objEntry = (ObjectList*)obj; xSemaphoreGiveRecursive(mutex);
if (!objEntry->isMetaobject) return res;
{ }
UAVObjSetData((UAVObjHandle)objEntry->linkedObj, dataIn);
} /**
else * Disconnect an event queue from the object.
{ * \param[in] obj The object handle
return -1; * \param[in] queue The event queue
} * \return 0 if success or -1 if failure
*/
// Unlock int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue)
xSemaphoreGiveRecursive(mutex); {
return 0; int32_t res;
} xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, queue, 0);
/** xSemaphoreGiveRecursive(mutex);
* Get the object metadata return res;
* \param[in] obj The object handle }
* \param[out] dataOut The object's metadata structure
* \return 0 if success or -1 if failure /**
*/ * Connect an event callback to the object, if the callback is already connected then the event mask is only updated.
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata* dataOut) * The supplied callback will be invoked on all events matching the event mask.
{ * \param[in] obj The object handle
ObjectList* objEntry; * \param[in] cb The event callback
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
// Lock * \return 0 if success or -1 if failure
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); */
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb,
// Get metadata int32_t eventMask)
objEntry = (ObjectList*)obj; {
if (objEntry->isMetaobject) int32_t res;
{ xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata)); res = connectObj(obj, 0, cb, eventMask);
} xSemaphoreGiveRecursive(mutex);
else return res;
{ }
UAVObjGetData((UAVObjHandle)objEntry->linkedObj, dataOut);
} /**
* Disconnect an event callback from the object.
// Unlock * \param[in] obj The object handle
xSemaphoreGiveRecursive(mutex); * \param[in] cb The event callback
return 0; * \return 0 if success or -1 if failure
} */
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb)
/** {
* Check if an object is read only int32_t res;
* \param[in] obj The object handle xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* \return res = disconnectObj(obj, 0, cb);
* \arg 0 if not read only xSemaphoreGiveRecursive(mutex);
* \arg 1 if read only return res;
* \arg -1 if unable to get meta data }
*/
int8_t UAVObjReadOnly(UAVObjHandle obj) /**
{ * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event
ObjectList* objEntry; * will be generated as soon as the object is updated.
UAVObjMetadata* mdata; * \param[in] obj The object handle
*/
// Cast to object info void UAVObjRequestUpdate(UAVObjHandle obj)
objEntry = (ObjectList*)obj; {
UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES);
// Check access level }
if ( !objEntry->isMetaobject )
{ /**
mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data); * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event
return mdata->access == ACCESS_READONLY; * will be generated as soon as the object is updated.
} * \param[in] obj The object handle
return -1; * \param[in] instId Object instance ID to update
} */
void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId)
/** {
* Connect an event queue to the object, if the queue is already connected then the event mask is only updated. xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* All events matching the event mask will be pushed to the event queue. sendEvent((ObjectList *) obj, instId, EV_UPDATE_REQ);
* \param[in] obj The object handle xSemaphoreGiveRecursive(mutex);
* \param[in] queue The event queue }
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
* \return 0 if success or -1 if failure /**
*/ * Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, int32_t eventMask) * \param[in] obj The object handle
{ */
int32_t res; void UAVObjUpdated(UAVObjHandle obj)
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); {
res = connectObj(obj, queue, 0, eventMask); UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES);
xSemaphoreGiveRecursive(mutex); }
return res;
} /**
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
/** * \param[in] obj The object handle
* Disconnect an event queue from the object. * \param[in] instId The object instance ID
* \param[in] obj The object handle */
* \param[in] queue The event queue void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId)
* \return 0 if success or -1 if failure {
*/ xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue) sendEvent((ObjectList *) obj, instId, EV_UPDATED_MANUAL);
{ xSemaphoreGiveRecursive(mutex);
int32_t res; }
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, queue, 0); /**
xSemaphoreGiveRecursive(mutex); * Iterate through all objects in the list.
return res; * \param iterator This function will be called once for each object,
} * the object will be passed as a parameter
*/
/** void UAVObjIterate(void (*iterator) (UAVObjHandle obj))
* Connect an event callback to the object, if the callback is already connected then the event mask is only updated. {
* The supplied callback will be invoked on all events matching the event mask. ObjectList *objEntry;
* \param[in] obj The object handle
* \param[in] cb The event callback // Get lock
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
* \return 0 if success or -1 if failure
*/ // Iterate through the list and invoke iterator for each object
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, int32_t eventMask) LL_FOREACH(objList, objEntry) {
{ (*iterator) ((UAVObjHandle) objEntry);
int32_t res; }
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = connectObj(obj, 0, cb, eventMask); // Release lock
xSemaphoreGiveRecursive(mutex); xSemaphoreGiveRecursive(mutex);
return res; }
}
/**
/** * Send an event to all event queues registered on the object.
* Disconnect an event callback from the object. */
* \param[in] obj The object handle static int32_t sendEvent(ObjectList * obj, uint16_t instId,
* \param[in] cb The event callback UAVObjEventType event)
* \return 0 if success or -1 if failure {
*/ ObjectEventList *eventEntry;
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb) UAVObjEvent msg;
{
int32_t res; // Setup event
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); msg.obj = (UAVObjHandle) obj;
res = disconnectObj(obj, 0, cb); msg.event = event;
xSemaphoreGiveRecursive(mutex); msg.instId = instId;
return res;
} // Go through each object and push the event message in the queue (if event is activated for the queue)
LL_FOREACH(obj->events, eventEntry) {
if (eventEntry->eventMask == 0
/** || (eventEntry->eventMask & event) != 0) {
* Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event // Send to queue if a valid queue is registered
* will be generated as soon as the object is updated. if (eventEntry->queue != 0) {
* \param[in] obj The object handle if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block
*/ {
void UAVObjRequestUpdate(UAVObjHandle obj) ++stats.eventErrors;
{ }
UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES); }
} // Invoke callback (from event task) if a valid one is registered
if (eventEntry->cb != 0) {
/** if (EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE) // invoke callback from the event task, will not block
* Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event {
* will be generated as soon as the object is updated. ++stats.eventErrors;
* \param[in] obj The object handle }
* \param[in] instId Object instance ID to update }
*/ }
void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId) }
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); // Done
sendEvent((ObjectList*)obj, instId, EV_UPDATE_REQ); return 0;
xSemaphoreGiveRecursive(mutex); }
}
/**
/** * Create a new object instance, return the instance info or NULL if failure.
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). */
* \param[in] obj The object handle static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId)
*/ {
void UAVObjUpdated(UAVObjHandle obj) ObjectInstList *instEntry;
{ int32_t n;
UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES);
} // For single instance objects, only instance zero is allowed
if (obj->isSingleInstance && instId != 0) {
/** return NULL;
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). }
* \param[in] obj The object handle // Make sure that the instance ID is within limits
* \param[in] instId The object instance ID if (instId >= UAVOBJ_MAX_INSTANCES) {
*/ return NULL;
void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId) }
{ // Check if the instance already exists
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); if (getInstance(obj, instId) != NULL) {
sendEvent((ObjectList*)obj, instId, EV_UPDATED_MANUAL); return NULL;
xSemaphoreGiveRecursive(mutex); }
} // Create any missing instances (all instance IDs must be sequential)
for (n = obj->numInstances; n < instId; ++n) {
/** if (createInstance(obj, n) == NULL) {
* Iterate through all objects in the list. return NULL;
* \param iterator This function will be called once for each object, }
* the object will be passed as a parameter }
*/
void UAVObjIterate(void (*iterator)(UAVObjHandle obj)) if (instId == 0) { /* Instance 0 ObjectInstList allocated with ObjectList element */
{ instEntry = &obj->instances;
ObjectList* objEntry; instEntry->data = pvPortMalloc(obj->numBytes);
if (instEntry->data == NULL)
// Get lock return NULL;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY); memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId;
// Iterate through the list and invoke iterator for each object } else {
LL_FOREACH(objList, objEntry) // Create the actual instance
{ instEntry =
(*iterator)((UAVObjHandle)objEntry); (ObjectInstList *)
} pvPortMalloc(sizeof(ObjectInstList));
if (instEntry == NULL)
// Release lock return NULL;
xSemaphoreGiveRecursive(mutex); instEntry->data = pvPortMalloc(obj->numBytes);
} if (instEntry->data == NULL)
return NULL;
/** memset(instEntry->data, 0, obj->numBytes);
* Send an event to all event queues registered on the object. instEntry->instId = instId;
*/ LL_APPEND(obj->instances.next, instEntry);
static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event) }
{ ++obj->numInstances;
ObjectEventList* eventEntry;
UAVObjEvent msg; // Fire event
UAVObjInstanceUpdated((UAVObjHandle) obj, instId);
// Setup event
msg.obj = (UAVObjHandle)obj; // Done
msg.event = event; return instEntry;
msg.instId = instId; }
// Go through each object and push the event message in the queue (if event is activated for the queue) /**
LL_FOREACH(obj->events, eventEntry) * Get the instance information or NULL if the instance does not exist
{ */
if ( eventEntry->eventMask == 0 || (eventEntry->eventMask & event) != 0 ) static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId)
{ {
// Send to queue if a valid queue is registered ObjectInstList *instEntry;
if (eventEntry->queue != 0)
{ // Look for specified instance ID
if ( xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE ) // will not block LL_FOREACH(&(obj->instances), instEntry) {
{ if (instEntry->instId == instId) {
++stats.eventErrors; return instEntry;
} }
} }
// Invoke callback (from event task) if a valid one is registered // If this point is reached then instance id was not found
if (eventEntry->cb != 0) return NULL;
{ }
if ( EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE ) // invoke callback from the event task, will not block
{ /**
++stats.eventErrors; * Connect an event queue to the object, if the queue is already connected then the event mask is only updated.
} * \param[in] obj The object handle
} * \param[in] queue The event queue
} * \param[in] cb The event callback
} * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
* \return 0 if success or -1 if failure
// Done */
return 0; static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
} UAVObjEventCallback cb, int32_t eventMask)
{
/** ObjectEventList *eventEntry;
* Create a new object instance, return the instance info or NULL if failure. ObjectList *objEntry;
*/
static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId) // Check that the queue is not already connected, if it is simply update event mask
{ objEntry = (ObjectList *) obj;
ObjectInstList* instEntry; LL_FOREACH(objEntry->events, eventEntry) {
int32_t n; if (eventEntry->queue == queue && eventEntry->cb == cb) {
// Already connected, update event mask and return
// For single instance objects, only instance zero is allowed eventEntry->eventMask = eventMask;
if (obj->isSingleInstance && instId != 0) return 0;
{ }
return NULL; }
}
// Add queue to list
// Make sure that the instance ID is within limits eventEntry =
if (instId >= UAVOBJ_MAX_INSTANCES) (ObjectEventList *) pvPortMalloc(sizeof(ObjectEventList));
{ if (eventEntry == NULL) {
return NULL; return -1;
} }
eventEntry->queue = queue;
// Check if the instance already exists eventEntry->cb = cb;
if ( getInstance(obj, instId) != NULL ) eventEntry->eventMask = eventMask;
{ LL_APPEND(objEntry->events, eventEntry);
return NULL;
} // Done
return 0;
// Create any missing instances (all instance IDs must be sequential) }
for (n = obj->numInstances; n < instId; ++n)
{ /**
if ( createInstance(obj, n) == NULL ) * Disconnect an event queue from the object
{ * \param[in] obj The object handle
return NULL; * \param[in] queue The event queue
} * \param[in] cb The event callback
} * \return 0 if success or -1 if failure
*/
if(instId == 0) /* Instance 0 ObjectInstList allocated with ObjectList element */ static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
{ UAVObjEventCallback cb)
instEntry = &obj->instances; {
instEntry->data = pvPortMalloc(obj->numBytes); ObjectEventList *eventEntry;
if (instEntry->data == NULL) return NULL; ObjectList *objEntry;
memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId; // Find queue and remove it
} else objEntry = (ObjectList *) obj;
{ LL_FOREACH(objEntry->events, eventEntry) {
// Create the actual instance if ((eventEntry->queue == queue
instEntry = (ObjectInstList*)pvPortMalloc(sizeof(ObjectInstList)); && eventEntry->cb == cb)) {
if (instEntry == NULL) return NULL; LL_DELETE(objEntry->events, eventEntry);
instEntry->data = pvPortMalloc(obj->numBytes); vPortFree(eventEntry);
if (instEntry->data == NULL) return NULL; return 0;
memset(instEntry->data, 0, obj->numBytes); }
instEntry->instId = instId; }
LL_APPEND(obj->instances.next, instEntry);
} // If this point is reached the queue was not found
++obj->numInstances; return -1;
}
// Fire event
UAVObjInstanceUpdated((UAVObjHandle)obj, instId); #if defined(PIOS_INCLUDE_SDCARD)
/**
// Done * Wrapper for the sprintf function
return instEntry; */
} static void customSPrintf(uint8_t * buffer, uint8_t * format, ...)
{
/** va_list args;
* Get the instance information or NULL if the instance does not exist va_start(args, format);
*/ vsprintf((char *)buffer, (char *)format, args);
static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId) }
{
ObjectInstList* instEntry; /**
* Get an 8 character (plus extension) filename for the object.
// Look for specified instance ID */
LL_FOREACH(&(obj->instances), instEntry) static void objectFilename(ObjectList * obj, uint8_t * filename)
{ {
if (instEntry->instId == instId) customSPrintf(filename, (uint8_t *) "%X.obj", obj->id);
{ }
return instEntry; #endif /* PIOS_INCLUDE_SDCARD */
}
}
// If this point is reached then instance id was not found
return NULL;
}
/**
* Connect an event queue to the object, if the queue is already connected then the event mask is only updated.
* \param[in] obj The object handle
* \param[in] queue The event queue
* \param[in] cb The event callback
* \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL)
* \return 0 if success or -1 if failure
*/
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb, int32_t eventMask)
{
ObjectEventList* eventEntry;
ObjectList* objEntry;
// Check that the queue is not already connected, if it is simply update event mask
objEntry = (ObjectList*)obj;
LL_FOREACH(objEntry->events, eventEntry)
{
if ( eventEntry->queue == queue && eventEntry->cb == cb )
{
// Already connected, update event mask and return
eventEntry->eventMask = eventMask;
return 0;
}
}
// Add queue to list
eventEntry = (ObjectEventList*)pvPortMalloc(sizeof(ObjectEventList));
if (eventEntry == NULL)
{
return -1;
}
eventEntry->queue = queue;
eventEntry->cb = cb;
eventEntry->eventMask = eventMask;
LL_APPEND(objEntry->events, eventEntry);
// Done
return 0;
}
/**
* Disconnect an event queue from the object
* \param[in] obj The object handle
* \param[in] queue The event queue
* \param[in] cb The event callback
* \return 0 if success or -1 if failure
*/
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb)
{
ObjectEventList* eventEntry;
ObjectList* objEntry;
// Find queue and remove it
objEntry = (ObjectList*)obj;
LL_FOREACH(objEntry->events, eventEntry)
{
if ( ( eventEntry->queue == queue && eventEntry->cb == cb ) )
{
LL_DELETE(objEntry->events, eventEntry);
vPortFree(eventEntry);
return 0;
}
}
// If this point is reached the queue was not found
return -1;
}
#if defined(PIOS_INCLUDE_SDCARD)
/**
* Wrapper for the sprintf function
*/
static void customSPrintf(uint8_t* buffer, uint8_t* format, ...)
{
va_list args;
va_start(args, format);
vsprintf((char *)buffer, (char *)format, args);
}
/**
* Get an 8 character (plus extension) filename for the object.
*/
static void objectFilename(ObjectList* obj, uint8_t* filename)
{
customSPrintf(filename, (uint8_t*)"%X.obj", obj->id);
}
#endif /* PIOS_INCLUDE_SDCARD */

View File

@ -21,6 +21,7 @@ alert
altitude altitude
amps amps
aquired aquired
armed
autonomous flight autonomous flight
battery battery
camera camera
@ -32,8 +33,10 @@ complete
connected connected
connection connection
control control
coptercontrol
critical critical
disabled disabled
disarmed
disconnected disconnected
feet feet
figure eight figure eight
@ -58,11 +61,13 @@ lost
low altitude low altitude
low battery low battery
low gps quality low gps quality
magic
manual flight manual flight
maxium maxium
meters meters
minimum minimum
mode mode
moved
MPH MPH
navigation navigation
OpenPilot OpenPilot
@ -122,8 +127,4 @@ hundread
thousand thousand
Upto: OpenPilot
critical
battery
point

View File

@ -1,5 +1,5 @@
[General] [General]
ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5V\0\0\x2\x9a\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0) ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5\xa0\0\0\x3/\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0)
[Workspace] [Workspace]
NumberOfWorkspaces=6 NumberOfWorkspaces=6
@ -7,7 +7,7 @@ Workspace1=Flight data
Icon1=:/core/images/ah.png Icon1=:/core/images/ah.png
Workspace2=Configuration Workspace2=Configuration
Icon2=:/core/images/config.png Icon2=:/core/images/config.png
Workspace3=Large Map Workspace3=Flight Planner
Icon3=:/core/images/world.png Icon3=:/core/images/world.png
Workspace4=Scopes Workspace4=Scopes
Icon4=:/core/images/scopes.png Icon4=:/core/images/scopes.png
@ -70,6 +70,7 @@ Mode1\splitter\side0\side1\splitterOrientation=1
Mode1\splitter\side0\side1\splitterSizes=304, 433 Mode1\splitter\side0\side1\splitterSizes=304, 433
Mode1\splitter\side0\side1\side0\type=uavGadget Mode1\splitter\side0\side1\side0\type=uavGadget
Mode1\splitter\side0\side1\side0\classId=ModelViewGadget Mode1\splitter\side0\side1\side0\classId=ModelViewGadget
Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X
Mode1\splitter\side0\side1\side1\type=splitter Mode1\splitter\side0\side1\side1\type=splitter
Mode1\splitter\side0\side1\side1\splitterOrientation=2 Mode1\splitter\side0\side1\side1\splitterOrientation=2
Mode1\splitter\side0\side1\side1\splitterSizes=293, 64 Mode1\splitter\side0\side1\side1\splitterSizes=293, 64
@ -180,7 +181,15 @@ Mode2\splitter\side0\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Ho
Mode2\splitter\side0\side1\side1\type=uavGadget Mode2\splitter\side0\side1\side1\type=uavGadget
Mode2\splitter\side0\side1\side1\classId=LineardialGadget Mode2\splitter\side0\side1\side1\classId=LineardialGadget
Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal
Mode2\splitter\side1\type=uavGadget Mode2\splitter\side1\type=splitter
Mode2\splitter\side1\splitterOrientation=2
Mode2\splitter\side1\splitterSizes=426, 354
Mode2\splitter\side1\side0\type=uavGadget
Mode2\splitter\side1\side0\classId=UAVObjectBrowser
Mode2\splitter\side1\side0\gadget\activeConfiguration=default
Mode2\splitter\side1\side1\type=uavGadget
Mode2\splitter\side1\side1\classId=GCSControlGadget
Mode2\splitter\side1\side1\gadget\activeConfiguration=MS Sidewinder
Mode3\version=UAVGadgetManagerV1 Mode3\version=UAVGadgetManagerV1
Mode3\showToolbars=false Mode3\showToolbars=false
Mode3\splitter\type=splitter Mode3\splitter\type=splitter
@ -194,6 +203,7 @@ Mode3\splitter\side1\splitterOrientation=2
Mode3\splitter\side1\splitterSizes=395, 236 Mode3\splitter\side1\splitterSizes=395, 236
Mode3\splitter\side1\side0\type=uavGadget Mode3\splitter\side1\side0\type=uavGadget
Mode3\splitter\side1\side0\classId=ModelViewGadget Mode3\splitter\side1\side0\classId=ModelViewGadget
Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X
Mode3\splitter\side1\side1\type=splitter Mode3\splitter\side1\side1\type=splitter
Mode3\splitter\side1\side1\splitterOrientation=1 Mode3\splitter\side1\side1\splitterOrientation=1
Mode3\splitter\side1\side1\splitterSizes=@Invalid() Mode3\splitter\side1\side1\splitterSizes=@Invalid()
@ -289,21 +299,13 @@ Mode6\splitter\side1\side0\side1\gadget\activeConfiguration=raw
Mode6\splitter\side1\side1\type=uavGadget Mode6\splitter\side1\side1\type=uavGadget
Mode6\splitter\side1\side1\classId=ScopeGadget Mode6\splitter\side1\side1\classId=ScopeGadget
Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes
Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X
Mode2\splitter\side1\classId=UAVObjectBrowser
Mode2\splitter\side1\gadget\activeConfiguration=default
Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X
[KeyBindings] [KeyBindings]
size=0 size=0
[%General] [%General]
OverrideLanguage=en_AU
SaveSettingsOnExit=true SaveSettingsOnExit=true
TerminalEmulator=xterm -e
LastPreferenceCategory=LineardialGadget
LastPreferencePage=Roll Desired 1
SettingsWindowWidth=921
SettingsWindowHeight=534
[UAVGadgetConfigurations] [UAVGadgetConfigurations]
configInfo\version=1.2.0 configInfo\version=1.2.0
@ -1233,6 +1235,40 @@ LineardialGadget\Mainboard%20CPU\data\factor=1
LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false
LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0 LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0
LineardialGadget\Mainboard%20CPU\configInfo\locked=false LineardialGadget\Mainboard%20CPU\configInfo\locked=false
LineardialGadget\Pitch\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Pitch\data\sourceDataObject=ManualControlCommand
LineardialGadget\Pitch\data\sourceObjectField=Pitch
LineardialGadget\Pitch\data\minValue=-1
LineardialGadget\Pitch\data\maxValue=1
LineardialGadget\Pitch\data\redMin=-1
LineardialGadget\Pitch\data\redMax=1
LineardialGadget\Pitch\data\yellowMin=-0.8
LineardialGadget\Pitch\data\yellowMax=0.8
LineardialGadget\Pitch\data\greenMin=-0.5
LineardialGadget\Pitch\data\greenMax=0.5
LineardialGadget\Pitch\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Pitch\data\decimalPlaces=2
LineardialGadget\Pitch\data\factor=1
LineardialGadget\Pitch\data\useOpenGLFlag=false
LineardialGadget\Pitch\configInfo\version=0.0.0
LineardialGadget\Pitch\configInfo\locked=false
LineardialGadget\Pitch%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Pitch%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Pitch%20Desired\data\sourceObjectField=Pitch
LineardialGadget\Pitch%20Desired\data\minValue=-1
LineardialGadget\Pitch%20Desired\data\maxValue=1
LineardialGadget\Pitch%20Desired\data\redMin=-1
LineardialGadget\Pitch%20Desired\data\redMax=1
LineardialGadget\Pitch%20Desired\data\yellowMin=-0.8
LineardialGadget\Pitch%20Desired\data\yellowMax=0.8
LineardialGadget\Pitch%20Desired\data\greenMin=-0.5
LineardialGadget\Pitch%20Desired\data\greenMax=0.5
LineardialGadget\Pitch%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Pitch%20Desired\data\decimalPlaces=2
LineardialGadget\Pitch%20Desired\data\factor=1
LineardialGadget\Pitch%20Desired\data\useOpenGLFlag=false
LineardialGadget\Pitch%20Desired\configInfo\version=0.0.0
LineardialGadget\Pitch%20Desired\configInfo\locked=false
LineardialGadget\PitchActual\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\PitchActual\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\PitchActual\data\sourceDataObject=AttitudeActual LineardialGadget\PitchActual\data\sourceDataObject=AttitudeActual
LineardialGadget\PitchActual\data\sourceObjectField=Pitch LineardialGadget\PitchActual\data\sourceObjectField=Pitch
@ -1267,6 +1303,23 @@ LineardialGadget\Roll\data\factor=1
LineardialGadget\Roll\data\useOpenGLFlag=false LineardialGadget\Roll\data\useOpenGLFlag=false
LineardialGadget\Roll\configInfo\version=0.0.0 LineardialGadget\Roll\configInfo\version=0.0.0
LineardialGadget\Roll\configInfo\locked=false LineardialGadget\Roll\configInfo\locked=false
LineardialGadget\Roll%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Roll%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Roll%20Desired\data\sourceObjectField=Roll
LineardialGadget\Roll%20Desired\data\minValue=-1
LineardialGadget\Roll%20Desired\data\maxValue=1
LineardialGadget\Roll%20Desired\data\redMin=-1
LineardialGadget\Roll%20Desired\data\redMax=1
LineardialGadget\Roll%20Desired\data\yellowMin=-0.8
LineardialGadget\Roll%20Desired\data\yellowMax=0.8
LineardialGadget\Roll%20Desired\data\greenMin=-0.5
LineardialGadget\Roll%20Desired\data\greenMax=0.5
LineardialGadget\Roll%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Roll%20Desired\data\decimalPlaces=2
LineardialGadget\Roll%20Desired\data\factor=1
LineardialGadget\Roll%20Desired\data\useOpenGLFlag=false
LineardialGadget\Roll%20Desired\configInfo\version=0.0.0
LineardialGadget\Roll%20Desired\configInfo\locked=false
LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats
LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate
@ -1335,6 +1388,23 @@ LineardialGadget\Yaw\data\factor=1
LineardialGadget\Yaw\data\useOpenGLFlag=false LineardialGadget\Yaw\data\useOpenGLFlag=false
LineardialGadget\Yaw\configInfo\version=0.0.0 LineardialGadget\Yaw\configInfo\version=0.0.0
LineardialGadget\Yaw\configInfo\locked=false LineardialGadget\Yaw\configInfo\locked=false
LineardialGadget\Yaw%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Yaw%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Yaw%20Desired\data\sourceObjectField=Yaw
LineardialGadget\Yaw%20Desired\data\minValue=-1
LineardialGadget\Yaw%20Desired\data\maxValue=1
LineardialGadget\Yaw%20Desired\data\redMin=-1
LineardialGadget\Yaw%20Desired\data\redMax=1
LineardialGadget\Yaw%20Desired\data\yellowMin=-0.8
LineardialGadget\Yaw%20Desired\data\yellowMax=0.8
LineardialGadget\Yaw%20Desired\data\greenMin=-0.5
LineardialGadget\Yaw%20Desired\data\greenMax=0.5
LineardialGadget\Yaw%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Yaw%20Desired\data\decimalPlaces=2
LineardialGadget\Yaw%20Desired\data\factor=1
LineardialGadget\Yaw%20Desired\data\useOpenGLFlag=false
LineardialGadget\Yaw%20Desired\configInfo\version=0.0.0
LineardialGadget\Yaw%20Desired\configInfo\locked=false
ModelViewGadget\Aeroquad%20%2B\data\acFilename=%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds ModelViewGadget\Aeroquad%20%2B\data\acFilename=%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds
ModelViewGadget\Aeroquad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png ModelViewGadget\Aeroquad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
ModelViewGadget\Aeroquad%20%2B\data\enableVbo=false ModelViewGadget\Aeroquad%20%2B\data\enableVbo=false
@ -1404,40 +1474,6 @@ OPMapGadget\Google%20Sat\data\showTileGridLines=false
OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache
OPMapGadget\Google%20Sat\data\useMemoryCache=true OPMapGadget\Google%20Sat\data\useMemoryCache=true
OPMapGadget\Google%20Sat\data\uavSymbol=mapquad.png OPMapGadget\Google%20Sat\data\uavSymbol=mapquad.png
LineardialGadget\Pitch\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Pitch\data\sourceDataObject=ManualControlCommand
LineardialGadget\Pitch\data\sourceObjectField=Pitch
LineardialGadget\Pitch\data\minValue=-1
LineardialGadget\Pitch\data\maxValue=1
LineardialGadget\Pitch\data\redMin=-1
LineardialGadget\Pitch\data\redMax=1
LineardialGadget\Pitch\data\yellowMin=-0.8
LineardialGadget\Pitch\data\yellowMax=0.8
LineardialGadget\Pitch\data\greenMin=-0.5
LineardialGadget\Pitch\data\greenMax=0.5
LineardialGadget\Pitch\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Pitch\data\decimalPlaces=2
LineardialGadget\Pitch\data\factor=1
LineardialGadget\Pitch\data\useOpenGLFlag=false
LineardialGadget\Pitch\configInfo\version=0.0.0
LineardialGadget\Pitch\configInfo\locked=false
LineardialGadget\Pitch%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Pitch%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Pitch%20Desired\data\sourceObjectField=Pitch
LineardialGadget\Pitch%20Desired\data\minValue=-1
LineardialGadget\Pitch%20Desired\data\maxValue=1
LineardialGadget\Pitch%20Desired\data\redMin=-1
LineardialGadget\Pitch%20Desired\data\redMax=1
LineardialGadget\Pitch%20Desired\data\yellowMin=-0.8
LineardialGadget\Pitch%20Desired\data\yellowMax=0.8
LineardialGadget\Pitch%20Desired\data\greenMin=-0.5
LineardialGadget\Pitch%20Desired\data\greenMax=0.5
LineardialGadget\Pitch%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Pitch%20Desired\data\decimalPlaces=2
LineardialGadget\Pitch%20Desired\data\factor=1
LineardialGadget\Pitch%20Desired\data\useOpenGLFlag=false
LineardialGadget\Pitch%20Desired\configInfo\version=0.0.0
LineardialGadget\Pitch%20Desired\configInfo\locked=false
OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache/
OPMapGadget\Google%20Sat\configInfo\version=0.0.0 OPMapGadget\Google%20Sat\configInfo\version=0.0.0
OPMapGadget\Google%20Sat\configInfo\locked=false OPMapGadget\Google%20Sat\configInfo\locked=false
@ -1875,52 +1911,18 @@ Uploader\default\data\defaultStopBits=0
Uploader\default\data\defaultPort=/dev/ttyS0 Uploader\default\data\defaultPort=/dev/ttyS0
Uploader\default\configInfo\version=0.0.0 Uploader\default\configInfo\version=0.0.0
Uploader\default\configInfo\locked=false Uploader\default\configInfo\locked=false
LineardialGadget\Roll%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Roll%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Roll%20Desired\data\sourceObjectField=Roll
LineardialGadget\Roll%20Desired\data\minValue=-1
LineardialGadget\Roll%20Desired\data\maxValue=1
LineardialGadget\Roll%20Desired\data\redMin=-1
LineardialGadget\Roll%20Desired\data\redMax=1
LineardialGadget\Roll%20Desired\data\yellowMin=-0.8
LineardialGadget\Roll%20Desired\data\yellowMax=0.8
LineardialGadget\Roll%20Desired\data\greenMin=-0.5
LineardialGadget\Roll%20Desired\data\greenMax=0.5
LineardialGadget\Roll%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Roll%20Desired\data\decimalPlaces=2
LineardialGadget\Roll%20Desired\data\factor=1
LineardialGadget\Roll%20Desired\data\useOpenGLFlag=false
LineardialGadget\Roll%20Desired\configInfo\version=0.0.0
LineardialGadget\Roll%20Desired\configInfo\locked=false
LineardialGadget\Yaw%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
LineardialGadget\Yaw%20Desired\data\sourceDataObject=ActuatorDesired
LineardialGadget\Yaw%20Desired\data\sourceObjectField=Yaw
LineardialGadget\Yaw%20Desired\data\minValue=-1
LineardialGadget\Yaw%20Desired\data\maxValue=1
LineardialGadget\Yaw%20Desired\data\redMin=-1
LineardialGadget\Yaw%20Desired\data\redMax=1
LineardialGadget\Yaw%20Desired\data\yellowMin=-0.8
LineardialGadget\Yaw%20Desired\data\yellowMax=0.8
LineardialGadget\Yaw%20Desired\data\greenMin=-0.5
LineardialGadget\Yaw%20Desired\data\greenMax=0.5
LineardialGadget\Yaw%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
LineardialGadget\Yaw%20Desired\data\decimalPlaces=2
LineardialGadget\Yaw%20Desired\data\factor=1
LineardialGadget\Yaw%20Desired\data\useOpenGLFlag=false
LineardialGadget\Yaw%20Desired\configInfo\version=0.0.0
LineardialGadget\Yaw%20Desired\configInfo\locked=false
[Plugins] [Plugins]
SoundNotifyPlugin\data\Current\1\SoundCollectionPath=%%DATAPATH%%sounds SoundNotifyPlugin\data\Current\1\SoundCollectionPath=
SoundNotifyPlugin\data\Current\1\CurrentLanguage=default SoundNotifyPlugin\data\Current\1\CurrentLanguage=
SoundNotifyPlugin\data\Current\1\ObjectField=Channel SoundNotifyPlugin\data\Current\1\ObjectField=
SoundNotifyPlugin\data\Current\1\DataObject=ActuatorCommand SoundNotifyPlugin\data\Current\1\DataObject=
SoundNotifyPlugin\data\Current\1\Value=Equal to SoundNotifyPlugin\data\Current\1\Value=
SoundNotifyPlugin\data\Current\1\ValueSpinBox=0 SoundNotifyPlugin\data\Current\1\ValueSpinBox=0
SoundNotifyPlugin\data\Current\1\Sound1= SoundNotifyPlugin\data\Current\1\Sound1=
SoundNotifyPlugin\data\Current\1\Sound2= SoundNotifyPlugin\data\Current\1\Sound2=
SoundNotifyPlugin\data\Current\1\Sound3= SoundNotifyPlugin\data\Current\1\Sound3=
SoundNotifyPlugin\data\Current\1\SayOrder=Never SoundNotifyPlugin\data\Current\1\SayOrder=
SoundNotifyPlugin\data\Current\1\Repeat= SoundNotifyPlugin\data\Current\1\Repeat=
SoundNotifyPlugin\data\Current\1\ExpireTimeout=0 SoundNotifyPlugin\data\Current\1\ExpireTimeout=0
SoundNotifyPlugin\data\Current\size=1 SoundNotifyPlugin\data\Current\size=1
@ -1928,9 +1930,3 @@ SoundNotifyPlugin\data\listNotifies\size=0
SoundNotifyPlugin\data\EnableSound=false SoundNotifyPlugin\data\EnableSound=false
SoundNotifyPlugin\configInfo\version=1.0.0 SoundNotifyPlugin\configInfo\version=1.0.0
SoundNotifyPlugin\configInfo\locked=false SoundNotifyPlugin\configInfo\locked=false
[IPconnection]
Current\1\HostName=
Current\1\Port=1
Current\1\UseTCP=0
Current\size=1

View File

@ -1,102 +1,116 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file opmapgadgetconfiguration.cpp * @file opmapgadgetconfiguration.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin * @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{ * @{
* @brief The OpenPilot Map plugin * @brief The OpenPilot Map plugin
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "opmapgadgetconfiguration.h" #include "opmapgadgetconfiguration.h"
#include "utils/pathutils.h" #include "utils/pathutils.h"
#include <QDir> #include <QDir>
OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) :
IUAVGadgetConfiguration(classId, parent), IUAVGadgetConfiguration(classId, parent),
m_mapProvider("GoogleHybrid"), m_mapProvider("GoogleHybrid"),
m_defaultZoom(2), m_defaultZoom(2),
m_defaultLatitude(0), m_defaultLatitude(0),
m_defaultLongitude(0), m_defaultLongitude(0),
m_useOpenGL(false), m_useOpenGL(false),
m_showTileGridLines(false), m_showTileGridLines(false),
m_accessMode("ServerAndCache"), m_accessMode("ServerAndCache"),
m_useMemoryCache(true), m_useMemoryCache(true),
m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()), m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()),
m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")) m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")),
{ m_maxUpdateRate(2000) // ms
{
//if a saved configuration exists load it
if(qSettings != 0) { //if a saved configuration exists load it
QString mapProvider = qSettings->value("mapProvider").toString(); if (qSettings != 0) {
int zoom = qSettings->value("defaultZoom").toInt();
double latitude= qSettings->value("defaultLatitude").toDouble(); QString mapProvider = qSettings->value("mapProvider").toString();
double longitude= qSettings->value("defaultLongitude").toDouble(); int zoom = qSettings->value("defaultZoom").toInt();
bool useOpenGL= qSettings->value("useOpenGL").toBool(); double latitude= qSettings->value("defaultLatitude").toDouble();
bool showTileGridLines= qSettings->value("showTileGridLines").toBool(); double longitude= qSettings->value("defaultLongitude").toDouble();
QString accessMode= qSettings->value("accessMode").toString(); bool useOpenGL= qSettings->value("useOpenGL").toBool();
bool useMemoryCache= qSettings->value("useMemoryCache").toBool(); bool showTileGridLines= qSettings->value("showTileGridLines").toBool();
QString cacheLocation= qSettings->value("cacheLocation").toString(); QString accessMode= qSettings->value("accessMode").toString();
QString uavSymbol=qSettings->value("uavSymbol").toString(); bool useMemoryCache= qSettings->value("useMemoryCache").toBool();
if (!mapProvider.isEmpty()) m_mapProvider = mapProvider; QString cacheLocation= qSettings->value("cacheLocation").toString();
m_defaultZoom = zoom; QString uavSymbol=qSettings->value("uavSymbol").toString();
m_defaultLatitude = latitude; int max_update_rate = qSettings->value("maxUpdateRate").toInt();
m_defaultLongitude = longitude;
m_useOpenGL = useOpenGL; if (!mapProvider.isEmpty()) m_mapProvider = mapProvider;
m_showTileGridLines = showTileGridLines; m_defaultZoom = zoom;
m_uavSymbol=uavSymbol; m_defaultLatitude = latitude;
if (!accessMode.isEmpty()) m_accessMode = accessMode; m_defaultLongitude = longitude;
m_useMemoryCache = useMemoryCache; m_useOpenGL = useOpenGL;
if (!cacheLocation.isEmpty()) m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation); m_showTileGridLines = showTileGridLines;
} m_uavSymbol = uavSymbol;
}
m_maxUpdateRate = max_update_rate;
IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone() if (m_maxUpdateRate < 100 || m_maxUpdateRate > 5000)
{ m_maxUpdateRate = 2000;
OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId());
if (!accessMode.isEmpty())
m->m_mapProvider = m_mapProvider; m_accessMode = accessMode;
m->m_defaultZoom = m_defaultZoom; m_useMemoryCache = useMemoryCache;
m->m_defaultLatitude = m_defaultLatitude; if (!cacheLocation.isEmpty())
m->m_defaultLongitude = m_defaultLongitude; m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation);
m->m_useOpenGL = m_useOpenGL; }
m->m_showTileGridLines = m_showTileGridLines; }
m->m_accessMode = m_accessMode;
m->m_useMemoryCache = m_useMemoryCache; IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone()
m->m_cacheLocation = m_cacheLocation; {
m->m_uavSymbol=m_uavSymbol; OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId());
return m;
} m->m_mapProvider = m_mapProvider;
m->m_defaultZoom = m_defaultZoom;
void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { m->m_defaultLatitude = m_defaultLatitude;
qSettings->setValue("mapProvider", m_mapProvider); m->m_defaultLongitude = m_defaultLongitude;
qSettings->setValue("defaultZoom", m_defaultZoom); m->m_useOpenGL = m_useOpenGL;
qSettings->setValue("defaultLatitude", m_defaultLatitude); m->m_showTileGridLines = m_showTileGridLines;
qSettings->setValue("defaultLongitude", m_defaultLongitude); m->m_accessMode = m_accessMode;
qSettings->setValue("useOpenGL", m_useOpenGL); m->m_useMemoryCache = m_useMemoryCache;
qSettings->setValue("showTileGridLines", m_showTileGridLines); m->m_cacheLocation = m_cacheLocation;
qSettings->setValue("accessMode", m_accessMode); m->m_uavSymbol = m_uavSymbol;
qSettings->setValue("useMemoryCache", m_useMemoryCache); m->m_maxUpdateRate = m_maxUpdateRate;
qSettings->setValue("uavSymbol", m_uavSymbol);
qSettings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); return m;
} }
void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){
m_cacheLocation = cacheLocation; void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const {
} qSettings->setValue("mapProvider", m_mapProvider);
qSettings->setValue("defaultZoom", m_defaultZoom);
qSettings->setValue("defaultLatitude", m_defaultLatitude);
qSettings->setValue("defaultLongitude", m_defaultLongitude);
qSettings->setValue("useOpenGL", m_useOpenGL);
qSettings->setValue("showTileGridLines", m_showTileGridLines);
qSettings->setValue("accessMode", m_accessMode);
qSettings->setValue("useMemoryCache", m_useMemoryCache);
qSettings->setValue("uavSymbol", m_uavSymbol);
qSettings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation));
qSettings->setValue("maxUpdateRate", m_maxUpdateRate);
}
void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){
m_cacheLocation = cacheLocation;
}

View File

@ -1,93 +1,97 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file opmapgadgetconfiguration.h * @file opmapgadgetconfiguration.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin * @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{ * @{
* @brief The OpenPilot Map plugin * @brief The OpenPilot Map plugin
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#ifndef OPMAP_GADGETCONFIGURATION_H #ifndef OPMAP_GADGETCONFIGURATION_H
#define OPMAP_GADGETCONFIGURATION_H #define OPMAP_GADGETCONFIGURATION_H
#include <coreplugin/iuavgadgetconfiguration.h> #include <coreplugin/iuavgadgetconfiguration.h>
#include <QtCore/QString> #include <QtCore/QString>
using namespace Core; using namespace Core;
class OPMapGadgetConfiguration : public IUAVGadgetConfiguration class OPMapGadgetConfiguration : public IUAVGadgetConfiguration
{ {
Q_OBJECT Q_OBJECT
Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider) Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider)
Q_PROPERTY(int zoommo READ zoom WRITE setZoom) Q_PROPERTY(int zoommo READ zoom WRITE setZoom)
Q_PROPERTY(double latitude READ latitude WRITE setLatitude) Q_PROPERTY(double latitude READ latitude WRITE setLatitude)
Q_PROPERTY(double longitude READ longitude WRITE setLongitude) Q_PROPERTY(double longitude READ longitude WRITE setLongitude)
Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL) Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL)
Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines) Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines)
Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode) Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode)
Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache) Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache)
Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation) Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation)
Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol) Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol)
Q_PROPERTY(int maxUpdateRate READ maxUpdateRate WRITE setMaxUpdateRate)
public:
explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); public:
explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone(); void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone();
QString mapProvider() const { return m_mapProvider; }
int zoom() const { return m_defaultZoom; } QString mapProvider() const { return m_mapProvider; }
double latitude() const { return m_defaultLatitude; } int zoom() const { return m_defaultZoom; }
double longitude() const { return m_defaultLongitude; } double latitude() const { return m_defaultLatitude; }
bool useOpenGL() const { return m_useOpenGL; } double longitude() const { return m_defaultLongitude; }
bool showTileGridLines() const { return m_showTileGridLines; } bool useOpenGL() const { return m_useOpenGL; }
QString accessMode() const { return m_accessMode; } bool showTileGridLines() const { return m_showTileGridLines; }
bool useMemoryCache() const { return m_useMemoryCache; } QString accessMode() const { return m_accessMode; }
QString cacheLocation() const { return m_cacheLocation; } bool useMemoryCache() const { return m_useMemoryCache; }
QString uavSymbol() const { return m_uavSymbol; } QString cacheLocation() const { return m_cacheLocation; }
QString uavSymbol() const { return m_uavSymbol; }
public slots: int maxUpdateRate() const { return m_maxUpdateRate; }
void setMapProvider(QString provider) { m_mapProvider = provider; }
void setZoom(int zoom) { m_defaultZoom = zoom; } public slots:
void setLatitude(double latitude) { m_defaultLatitude = latitude; } void setMapProvider(QString provider) { m_mapProvider = provider; }
void setLongitude(double longitude) { m_defaultLongitude = longitude; } void setZoom(int zoom) { m_defaultZoom = zoom; }
void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; } void setLatitude(double latitude) { m_defaultLatitude = latitude; }
void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; } void setLongitude(double longitude) { m_defaultLongitude = longitude; }
void setAccessMode(QString accessMode) { m_accessMode = accessMode; } void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; }
void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; } void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; }
void setCacheLocation(QString cacheLocation); void setAccessMode(QString accessMode) { m_accessMode = accessMode; }
void setUavSymbol(QString symbol){m_uavSymbol=symbol;} void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; }
private: void setCacheLocation(QString cacheLocation);
QString m_mapProvider; void setUavSymbol(QString symbol){m_uavSymbol=symbol;}
int m_defaultZoom; void setMaxUpdateRate(int update_rate){m_maxUpdateRate = update_rate;}
double m_defaultLatitude;
double m_defaultLongitude; private:
bool m_useOpenGL; QString m_mapProvider;
bool m_showTileGridLines; int m_defaultZoom;
QString m_accessMode; double m_defaultLatitude;
bool m_useMemoryCache; double m_defaultLongitude;
QString m_cacheLocation; bool m_useOpenGL;
QString m_uavSymbol; bool m_showTileGridLines;
QString m_accessMode;
}; bool m_useMemoryCache;
QString m_cacheLocation;
#endif // OPMAP_GADGETCONFIGURATION_H QString m_uavSymbol;
int m_maxUpdateRate;
};
#endif // OPMAP_GADGETCONFIGURATION_H

View File

@ -1,133 +1,149 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file opmapgadgetoptionspage.cpp * @file opmapgadgetoptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin * @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{ * @{
* @brief The OpenPilot Map plugin * @brief The OpenPilot Map plugin
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "opmapgadgetoptionspage.h" #include "opmapgadgetoptionspage.h"
#include "opmapgadgetconfiguration.h" #include "opmapgadgetconfiguration.h"
#include <QtGui/QLabel> #include <QtGui/QLabel>
#include <QtGui/QComboBox> #include <QtGui/QComboBox>
#include <QtGui/QSpinBox> #include <QtGui/QSpinBox>
#include <QtGui/QDoubleSpinBox> #include <QtGui/QDoubleSpinBox>
#include <QtGui/QHBoxLayout> #include <QtGui/QHBoxLayout>
#include <QtGui/QVBoxLayout> #include <QtGui/QVBoxLayout>
#include <QtGui/QFileDialog> #include <QtGui/QFileDialog>
#include "opmapcontrol/opmapcontrol.h" #include "opmapcontrol/opmapcontrol.h"
#include "utils/pathutils.h" #include "utils/pathutils.h"
#include "ui_opmapgadgetoptionspage.h" #include "ui_opmapgadgetoptionspage.h"
// ********************************************* // *********************************************
OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) : OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) :
IOptionsPage(parent), IOptionsPage(parent),
m_config(config) m_config(config)
{ {
} }
QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent) QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent)
{ {
m_page = new Ui::OPMapGadgetOptionsPage(); int index;
QWidget *w = new QWidget(parent);
m_page->setupUi(w); m_page = new Ui::OPMapGadgetOptionsPage();
QWidget *w = new QWidget(parent);
// populate the map provider combobox m_page->setupUi(w);
m_page->providerComboBox->clear();
m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes()); // populate the map provider combobox
m_page->providerComboBox->clear();
// populate the access mode combobox m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes());
m_page->accessModeComboBox->clear();
m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes()); // populate the access mode combobox
m_page->accessModeComboBox->clear();
int index = m_page->providerComboBox->findText(m_config->mapProvider()); m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes());
index = (index >= 0) ? index : 0;
m_page->providerComboBox->setCurrentIndex(index); index = m_page->providerComboBox->findText(m_config->mapProvider());
index = (index >= 0) ? index : 0;
m_page->zoomSpinBox->setValue(m_config->zoom()); m_page->providerComboBox->setCurrentIndex(index);
m_page->latitudeSpinBox->setValue(m_config->latitude());
m_page->longitudeSpinBox->setValue(m_config->longitude()); // populate the map max update rate combobox
m_page->maxUpdateRateComboBox->clear();
m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL()); m_page->maxUpdateRateComboBox->addItem("100ms", 100);
m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines()); m_page->maxUpdateRateComboBox->addItem("200ms", 200);
m_page->maxUpdateRateComboBox->addItem("500ms", 500);
index = m_page->accessModeComboBox->findText(m_config->accessMode()); m_page->maxUpdateRateComboBox->addItem("1 sec", 1000);
index = (index >= 0) ? index : 0; m_page->maxUpdateRateComboBox->addItem("2 sec", 2000);
m_page->accessModeComboBox->setCurrentIndex(index); m_page->maxUpdateRateComboBox->addItem("5 sec", 5000);
m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache()); index = m_page->maxUpdateRateComboBox->findData(m_config->maxUpdateRate());
index = (index >= 0) ? index : 4;
m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory); m_page->maxUpdateRateComboBox->setCurrentIndex(index);
m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory"));
m_page->lineEditCacheLocation->setPath(m_config->cacheLocation()); m_page->zoomSpinBox->setValue(m_config->zoom());
m_page->latitudeSpinBox->setValue(m_config->latitude());
QDir dir(":/uavs/images/"); m_page->longitudeSpinBox->setValue(m_config->longitude());
QStringList list=dir.entryList();
foreach(QString i,list) m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL());
{ m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines());
QIcon icon(QPixmap(":/uavs/images/"+i));
m_page->uavSymbolComboBox->addItem(icon,QString(),i); index = m_page->accessModeComboBox->findText(m_config->accessMode());
} index = (index >= 0) ? index : 0;
for(int x=0;x<m_page->uavSymbolComboBox->count();++x) m_page->accessModeComboBox->setCurrentIndex(index);
{
if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol()) m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache());
{
m_page->uavSymbolComboBox->setCurrentIndex(x); m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory);
} m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory"));
} m_page->lineEditCacheLocation->setPath(m_config->cacheLocation());
connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked())); QDir dir(":/uavs/images/");
QStringList list=dir.entryList();
return w; foreach(QString i,list)
} {
QIcon icon(QPixmap(":/uavs/images/"+i));
void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked() m_page->uavSymbolComboBox->addItem(icon,QString(),i);
{ }
int index = m_page->accessModeComboBox->findText("ServerAndCache"); for(int x=0;x<m_page->uavSymbolComboBox->count();++x)
index = (index >= 0) ? index : 0; {
m_page->accessModeComboBox->setCurrentIndex(index); if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol())
{
m_page->checkBoxUseMemoryCache->setChecked(true); m_page->uavSymbolComboBox->setCurrentIndex(x);
m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()); }
}
}
connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked()));
void OPMapGadgetOptionsPage::apply()
{ return w;
m_config->setMapProvider(m_page->providerComboBox->currentText()); }
m_config->setZoom(m_page->zoomSpinBox->value());
m_config->setLatitude(m_page->latitudeSpinBox->value()); void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked()
m_config->setLongitude(m_page->longitudeSpinBox->value()); {
m_config->setUseOpenGL(m_page->checkBoxUseOpenGL->isChecked()); int index = m_page->accessModeComboBox->findText("ServerAndCache");
m_config->setShowTileGridLines(m_page->checkBoxShowTileGridLines->isChecked()); index = (index >= 0) ? index : 0;
m_config->setAccessMode(m_page->accessModeComboBox->currentText()); m_page->accessModeComboBox->setCurrentIndex(index);
m_config->setUseMemoryCache(m_page->checkBoxUseMemoryCache->isChecked());
m_config->setCacheLocation(m_page->lineEditCacheLocation->path()); m_page->checkBoxUseMemoryCache->setChecked(true);
m_config->setUavSymbol(m_page->uavSymbolComboBox->itemData(m_page->uavSymbolComboBox->currentIndex()).toString()); m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator());
}
}
void OPMapGadgetOptionsPage::finish()
{ void OPMapGadgetOptionsPage::apply()
delete m_page; {
} m_config->setMapProvider(m_page->providerComboBox->currentText());
m_config->setZoom(m_page->zoomSpinBox->value());
m_config->setLatitude(m_page->latitudeSpinBox->value());
m_config->setLongitude(m_page->longitudeSpinBox->value());
m_config->setUseOpenGL(m_page->checkBoxUseOpenGL->isChecked());
m_config->setShowTileGridLines(m_page->checkBoxShowTileGridLines->isChecked());
m_config->setAccessMode(m_page->accessModeComboBox->currentText());
m_config->setUseMemoryCache(m_page->checkBoxUseMemoryCache->isChecked());
m_config->setCacheLocation(m_page->lineEditCacheLocation->path());
m_config->setUavSymbol(m_page->uavSymbolComboBox->itemData(m_page->uavSymbolComboBox->currentIndex()).toString());
m_config->setMaxUpdateRate(m_page->maxUpdateRateComboBox->itemData(m_page->maxUpdateRateComboBox->currentIndex()).toInt());
}
void OPMapGadgetOptionsPage::finish()
{
delete m_page;
}

View File

@ -30,7 +30,7 @@
<number>5</number> <number>5</number>
</property> </property>
<item row="1" column="0"> <item row="1" column="0">
<layout class="QGridLayout" name="gridLayout_3" rowstretch="0,0,0,0,0" rowminimumheight="22,22,22,0,22"> <layout class="QGridLayout" name="gridLayout_3" rowstretch="0,0,0,0,0,0" rowminimumheight="22,22,22,0,22,0">
<item row="2" column="0"> <item row="2" column="0">
<spacer name="horizontalSpacer_4"> <spacer name="horizontalSpacer_4">
<property name="orientation"> <property name="orientation">
@ -249,6 +249,19 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="3">
<widget class="QComboBox" name="maxUpdateRateComboBox"/>
</item>
<item row="5" column="2">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Default Max Update Rate </string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout> </layout>
</item> </item>
<item row="8" column="0"> <item row="8" column="0">

View File

@ -1,2371 +1,2451 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file opmapgadgetwidget.cpp * @file opmapgadgetwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin * @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{ * @{
* @brief The OpenPilot Map plugin * @brief The OpenPilot Map plugin
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "opmapgadgetwidget.h" #include "opmapgadgetwidget.h"
#include "ui_opmap_widget.h" #include "ui_opmap_widget.h"
#include <QtGui/QApplication> #include <QtGui/QApplication>
#include <QtGui/QHBoxLayout> #include <QtGui/QHBoxLayout>
#include <QtGui/QVBoxLayout> #include <QtGui/QVBoxLayout>
#include <QtGui/QClipboard> #include <QtGui/QClipboard>
#include <QtGui/QMenu> #include <QtGui/QMenu>
#include <QStringList> #include <QStringList>
#include <QDir> #include <QDir>
#include <QFile> #include <QFile>
#include <QDateTime> #include <QDateTime>
#include <math.h> #include <math.h>
#include "utils/stylehelper.h" #include "utils/stylehelper.h"
#include "utils/homelocationutil.h" #include "utils/homelocationutil.h"
#include "utils/worldmagmodel.h" #include "utils/worldmagmodel.h"
#include "uavtalk/telemetrymanager.h" #include "uavtalk/telemetrymanager.h"
#include "positionactual.h" #include "positionactual.h"
#include "homelocation.h" #include "homelocation.h"
#define allow_manual_home_location_move #define allow_manual_home_location_move
// ************************************************************************************* // *************************************************************************************
#define deg_to_rad ((double)M_PI / 180.0) #define deg_to_rad ((double)M_PI / 180.0)
#define rad_to_deg (180.0 / (double)M_PI) #define rad_to_deg (180.0 / (double)M_PI)
#define earth_mean_radius 6371 // kilometers #define earth_mean_radius 6371 // kilometers
#define max_digital_zoom 3 // maximum allowed digital zoom level #define max_digital_zoom 3 // maximum allowed digital zoom level
const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000}; // meters const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000}; // meters
const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds
const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters
// ************************************************************************************* const int max_update_rate_list[] = {100, 200, 500, 1000, 2000, 5000}; // milliseconds
// *************************************************************************************
// *************************************************************************************
// NOTE: go back to SVN REV 2137 and earlier to get back to experimental waypoint support.
// ************************************************************************************* // *************************************************************************************
// NOTE: go back to SVN REV 2137 and earlier to get back to experimental waypoint support.
// *************************************************************************************
// constructor
OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent)
{ // constructor
// ************** OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent)
{
m_widget = NULL; // **************
m_map = NULL;
findPlaceCompleter = NULL; m_widget = NULL;
m_map = NULL;
m_mouse_waypoint = NULL; findPlaceCompleter = NULL;
pm = NULL; m_mouse_waypoint = NULL;
obm = NULL;
obum = NULL; pm = NULL;
obm = NULL;
prev_tile_number = 0; obum = NULL;
min_zoom = max_zoom = 0; m_prev_tile_number = 0;
m_map_mode = Normal_MapMode; m_min_zoom = m_max_zoom = 0;
telemetry_connected = false; m_map_mode = Normal_MapMode;
context_menu_lat_lon = mouse_lat_lon = internals::PointLatLng(0, 0); m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds
setMouseTracking(true); m_telemetry_connected = false;
pm = ExtensionSystem::PluginManager::instance(); m_context_menu_lat_lon = m_mouse_lat_lon = internals::PointLatLng(0, 0);
if (pm)
{ setMouseTracking(true);
obm = pm->getObject<UAVObjectManager>();
obum = pm->getObject<UAVObjectUtilManager>(); pm = ExtensionSystem::PluginManager::instance();
} if (pm)
{
// ************** obm = pm->getObject<UAVObjectManager>();
// get current location obum = pm->getObject<UAVObjectUtilManager>();
}
double latitude = 0;
double longitude = 0; // **************
double altitude = 0; // get current location
// current position double latitude = 0;
getUAVPosition(latitude, longitude, altitude); double longitude = 0;
double altitude = 0;
internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude);
// current position
// ************** getUAVPosition(latitude, longitude, altitude);
// default home position
internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude);
home_position.coord = pos_lat_lon;
home_position.altitude = altitude; // **************
home_position.locked = false; // default home position
// ************** m_home_position.coord = pos_lat_lon;
// default magic waypoint params m_home_position.altitude = altitude;
m_home_position.locked = false;
magic_waypoint.map_wp_item = NULL;
magic_waypoint.coord = home_position.coord; // **************
magic_waypoint.altitude = altitude; // default magic waypoint params
magic_waypoint.description = "Magic waypoint";
magic_waypoint.locked = false; m_magic_waypoint.map_wp_item = NULL;
magic_waypoint.time_seconds = 0; m_magic_waypoint.coord = m_home_position.coord;
magic_waypoint.hold_time_seconds = 0; m_magic_waypoint.altitude = altitude;
m_magic_waypoint.description = "Magic waypoint";
// ************** m_magic_waypoint.locked = false;
// create the widget that holds the user controls and the map m_magic_waypoint.time_seconds = 0;
m_magic_waypoint.hold_time_seconds = 0;
m_widget = new Ui::OPMap_Widget();
m_widget->setupUi(this); // **************
// create the widget that holds the user controls and the map
// **************
// create the central map widget m_widget = new Ui::OPMap_Widget();
m_widget->setupUi(this);
m_map = new mapcontrol::OPMapWidget(); // create the map object
// **************
m_map->setFrameStyle(QFrame::NoFrame); // no border frame // create the central map widget
m_map->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); // tile background
m_map = new mapcontrol::OPMapWidget(); // create the map object
m_map->configuration->DragButton = Qt::LeftButton; // use the left mouse button for map dragging
m_map->setFrameStyle(QFrame::NoFrame); // no border frame
m_widget->horizontalSliderZoom->setMinimum(m_map->MinZoom()); // m_map->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); // tile background
m_widget->horizontalSliderZoom->setMaximum(m_map->MaxZoom() + max_digital_zoom); //
m_map->configuration->DragButton = Qt::LeftButton; // use the left mouse button for map dragging
min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept
max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept m_widget->horizontalSliderZoom->setMinimum(m_map->MinZoom()); //
m_widget->horizontalSliderZoom->setMaximum(m_map->MaxZoom() + max_digital_zoom); //
m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions
m_map->SetFollowMouse(true); // we want a contiuous mouse position reading m_min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept
m_max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept
m_map->SetShowHome(true); // display the HOME position on the map
m_map->SetShowUAV(true); // display the UAV position on the map m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions
m_map->SetFollowMouse(true); // we want a contiuous mouse position reading
m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters)
m_map->Home->SetShowSafeArea(true); // show the safe area m_map->SetShowHome(true); // display the HOME position on the map
m_map->SetShowUAV(true); // display the UAV position on the map
m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds
m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters)
m_map->Home->SetShowSafeArea(true); // show the safe area
m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed);
// m_map->UAV->SetTrailType(UAVTrailType::ByDistance); m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds
m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters
m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds
m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed);
// m_map->UAV->SetTrailType(UAVTrailType::ByDistance);
m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed);
// m_map->GPS->SetTrailType(UAVTrailType::ByDistance); m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds
m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters
// **************
m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed);
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); // m_map->GPS->SetTrailType(UAVTrailType::ByDistance);
QVBoxLayout *layout = new QVBoxLayout; // **************
layout->setSpacing(0);
layout->setContentsMargins(0, 0, 0, 0); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
layout->addWidget(m_map);
m_widget->mapWidget->setLayout(layout); QVBoxLayout *layout = new QVBoxLayout;
layout->setSpacing(0);
// ************** layout->setContentsMargins(0, 0, 0, 0);
// set the user control options layout->addWidget(m_map);
m_widget->mapWidget->setLayout(layout);
// TODO: this switch does not make sense, does it??
// **************
switch (m_map_mode) // set the user control options
{
case Normal_MapMode: // TODO: this switch does not make sense, does it??
m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
m_widget->toolButtonNormalMapMode->setChecked(true); switch (m_map_mode)
hideMagicWaypointControls(); {
break; case Normal_MapMode:
m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
case MagicWaypoint_MapMode: m_widget->toolButtonNormalMapMode->setChecked(true);
m_widget->toolButtonNormalMapMode->setChecked(false); hideMagicWaypointControls();
m_widget->toolButtonMagicWaypointMapMode->setChecked(true); break;
showMagicWaypointControls();
break; case MagicWaypoint_MapMode:
m_widget->toolButtonNormalMapMode->setChecked(false);
default: m_widget->toolButtonMagicWaypointMapMode->setChecked(true);
m_map_mode = Normal_MapMode; showMagicWaypointControls();
m_widget->toolButtonMagicWaypointMapMode->setChecked(false); break;
m_widget->toolButtonNormalMapMode->setChecked(true);
hideMagicWaypointControls(); default:
break; m_map_mode = Normal_MapMode;
} m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
m_widget->toolButtonNormalMapMode->setChecked(true);
m_widget->labelUAVPos->setText("---"); hideMagicWaypointControls();
m_widget->labelMapPos->setText("---"); break;
m_widget->labelMousePos->setText("---"); }
m_widget->labelMapZoom->setText("---");
m_widget->labelUAVPos->setText("---");
m_widget->labelMapPos->setText("---");
// Splitter is not used at the moment: m_widget->labelMousePos->setText("---");
// m_widget->splitter->setCollapsible(1, false); m_widget->labelMapZoom->setText("---");
// set the size of the collapsable widgets
//QList<int> m_SizeList; // Splitter is not used at the moment:
//m_SizeList << 0 << 0 << 0; // m_widget->splitter->setCollapsible(1, false);
//m_widget->splitter->setSizes(m_SizeList);
// set the size of the collapsable widgets
m_widget->progressBarMap->setMaximum(1); //QList<int> m_SizeList;
//m_SizeList << 0 << 0 << 0;
/* //m_widget->splitter->setSizes(m_SizeList);
#if defined(Q_OS_MAC)
#elif defined(Q_OS_WIN) m_widget->progressBarMap->setMaximum(1);
m_widget->comboBoxFindPlace->clear();
loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); /*
m_widget->comboBoxFindPlace->setCurrentIndex(-1); #if defined(Q_OS_MAC)
#else #elif defined(Q_OS_WIN)
#endif m_widget->comboBoxFindPlace->clear();
*/ loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt");
m_widget->comboBoxFindPlace->setCurrentIndex(-1);
#else
// ************** #endif
// map stuff */
connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals
connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals // **************
connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals // map stuff
connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals
connect(m_map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals
connect(m_map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals
connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals
connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals
connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals connect(m_map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals
connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); connect(m_map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed
connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed
connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error
connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals
connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*)));
m_map->SetCurrentPosition(home_position.coord); // set the map position connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*)));
m_map->Home->SetCoord(home_position.coord); // set the HOME position connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*)));
m_map->UAV->SetUAVPos(home_position.coord, 0.0); // set the UAV position connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&)));
m_map->GPS->SetUAVPos(home_position.coord, 0.0); // set the UAV position
m_map->SetCurrentPosition(m_home_position.coord); // set the map position
// ************** m_map->Home->SetCoord(m_home_position.coord); // set the HOME position
// create various context menu (mouse right click menu) actions m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position
m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position
createActions();
// **************
// ************** // create various context menu (mouse right click menu) actions
// connect to the UAVObject updates we require to become a bit aware of our environment:
createActions();
if (pm)
{ // **************
// Register for Home Location state changes // connect to the UAVObject updates we require to become a bit aware of our environment:
if (obm)
{ if (pm)
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(obm->getObject(QString("HomeLocation"))); {
if (obj) // Register for Home Location state changes
{ if (obm)
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); {
} UAVDataObject *obj = dynamic_cast<UAVDataObject *>(obm->getObject(QString("HomeLocation")));
} if (obj)
{
// Listen to telemetry connection events connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *)));
TelemetryManager *telMngr = pm->getObject<TelemetryManager>(); }
if (telMngr) }
{
connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); // Listen to telemetry connection events
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
} if (telMngr)
} {
connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect()));
// ************** connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect()));
// create the desired timers }
}
m_updateTimer = new QTimer();
m_updateTimer->setInterval(200); // **************
connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updatePosition())); // create the desired timers
m_updateTimer->start();
m_updateTimer = new QTimer();
m_statusUpdateTimer = new QTimer(); m_updateTimer->setInterval(m_maxUpdateRate);
m_statusUpdateTimer->setInterval(100); connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updatePosition()));
connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); m_updateTimer->start();
m_statusUpdateTimer->start();
m_statusUpdateTimer = new QTimer();
// ************** m_statusUpdateTimer->setInterval(200);
// m_statusUpdateTimer->setInterval(m_maxUpdateRate);
m_map->setFocus(); connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos()));
} m_statusUpdateTimer->start();
// destructor // **************
OPMapGadgetWidget::~OPMapGadgetWidget()
{ m_map->setFocus();
if (m_map) }
{
disconnect(m_map, 0, 0, 0); // destructor
m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit OPMapGadgetWidget::~OPMapGadgetWidget()
m_map->SetShowUAV(false); // " " {
} if (m_map)
{
disconnect(m_map, 0, 0, 0);
// this destructor doesn't appear to be called at shutdown??? m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit
m_map->SetShowUAV(false); // " "
// #if defined(Q_OS_MAC) }
// #elif defined(Q_OS_WIN)
// saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt");
// #else // this destructor doesn't appear to be called at shutdown???
// #endif
// #if defined(Q_OS_MAC)
m_waypoint_list_mutex.lock(); // #elif defined(Q_OS_WIN)
foreach (t_waypoint *wp, m_waypoint_list) // saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt");
{ // #else
if (!wp) continue; // #endif
m_waypoint_list_mutex.lock();
// todo: foreach (t_waypoint *wp, m_waypoint_list)
{
if (!wp) continue;
delete wp->map_wp_item;
}
m_waypoint_list_mutex.unlock(); // todo:
m_waypoint_list.clear();
if (m_map) delete wp->map_wp_item;
{ }
delete m_map; m_waypoint_list_mutex.unlock();
m_map = NULL; m_waypoint_list.clear();
}
} if (m_map)
{
// ************************************************************************************* delete m_map;
// widget signals .. the mouseMoveEvent does not get called - don't yet know why m_map = NULL;
}
void OPMapGadgetWidget::resizeEvent(QResizeEvent *event) }
{
qDebug("opmap: resizeEvent"); // *************************************************************************************
// widget signals .. the mouseMoveEvent does not get called - don't yet know why
QWidget::resizeEvent(event);
} void OPMapGadgetWidget::resizeEvent(QResizeEvent *event)
{
void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) qDebug("opmap: resizeEvent");
{
qDebug("opmap: mouseMoveEvent"); QWidget::resizeEvent(event);
}
if (m_widget && m_map)
{ void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event)
} {
qDebug("opmap: mouseMoveEvent");
if (event->buttons() & Qt::LeftButton)
{ if (m_widget && m_map)
// QPoint pos = event->pos(); {
} }
QWidget::mouseMoveEvent(event); if (event->buttons() & Qt::LeftButton)
} {
// QPoint pos = event->pos();
void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) }
{ // the user has right clicked on the map - create the pop-up context menu and display it
QWidget::mouseMoveEvent(event);
QString s; }
if (!m_widget || !m_map) void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event)
return; { // the user has right clicked on the map - create the pop-up context menu and display it
if (event->reason() != QContextMenuEvent::Mouse) QString s;
return; // not a mouse click event
if (!m_widget || !m_map)
// current mouse position return;
QPoint p = m_map->mapFromGlobal(event->globalPos());
context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); if (event->reason() != QContextMenuEvent::Mouse)
// context_menu_lat_lon = m_map->currentMousePosition(); return; // not a mouse click event
if (!m_map->contentsRect().contains(p)) // current mouse position
return; // the mouse click was not on the map QPoint p = m_map->mapFromGlobal(event->globalPos());
m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p);
// show the mouse position // m_context_menu_lat_lon = m_map->currentMousePosition();
s = QString::number(context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(context_menu_lat_lon.Lng(), 'f', 7);
m_widget->labelMousePos->setText(s); if (!m_map->contentsRect().contains(p))
return; // the mouse click was not on the map
// find out if we have a waypoint under the mouse cursor
QGraphicsItem *item = m_map->itemAt(p); // show the mouse position
m_mouse_waypoint = qgraphicsitem_cast<mapcontrol::WayPointItem *>(item); s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7);
m_widget->labelMousePos->setText(s);
// find out if the waypoint is locked (or not)
bool waypoint_locked = false; // find out if we have a waypoint under the mouse cursor
if (m_mouse_waypoint) QGraphicsItem *item = m_map->itemAt(p);
waypoint_locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; m_mouse_waypoint = qgraphicsitem_cast<mapcontrol::WayPointItem *>(item);
// **************** // find out if the waypoint is locked (or not)
// Dynamically create the popup menu bool waypoint_locked = false;
if (m_mouse_waypoint)
QMenu menu(this); waypoint_locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0;
menu.addAction(closeAct1); // ****************
// Dynamically create the popup menu
menu.addSeparator();
QMenu menu(this);
menu.addAction(reloadAct);
menu.addAction(closeAct1);
menu.addSeparator();
menu.addSeparator();
switch (m_map_mode)
{ menu.addAction(reloadAct);
case Normal_MapMode: s = tr(" (Normal)"); break;
case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break; menu.addSeparator();
default: s = tr(" (Unknown)"); break;
} QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this);
for (int i = 0; i < mapModeAct.count(); i++) for (int i = 0; i < maxUpdateRateAct.count(); i++)
{ // set the menu to checked (or not) maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i));
QAction *act = mapModeAct.at(i); menu.addMenu(&maxUpdateRateSubMenu);
if (!act) continue;
if (act->data().toInt() == (int)m_map_mode) menu.addSeparator();
act->setChecked(true);
} switch (m_map_mode)
QMenu mapModeSubMenu(tr("Map mode") + s, this); {
for (int i = 0; i < mapModeAct.count(); i++) case Normal_MapMode: s = tr(" (Normal)"); break;
mapModeSubMenu.addAction(mapModeAct.at(i)); case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break;
menu.addMenu(&mapModeSubMenu); default: s = tr(" (Unknown)"); break;
}
menu.addSeparator(); for (int i = 0; i < mapModeAct.count(); i++)
{ // set the menu to checked (or not)
QMenu copySubMenu(tr("Copy"), this); QAction *act = mapModeAct.at(i);
copySubMenu.addAction(copyMouseLatLonToClipAct); if (!act) continue;
copySubMenu.addAction(copyMouseLatToClipAct); if (act->data().toInt() == (int)m_map_mode)
copySubMenu.addAction(copyMouseLonToClipAct); act->setChecked(true);
menu.addMenu(&copySubMenu); }
QMenu mapModeSubMenu(tr("Map mode") + s, this);
menu.addSeparator(); for (int i = 0; i < mapModeAct.count(); i++)
mapModeSubMenu.addAction(mapModeAct.at(i));
/* menu.addMenu(&mapModeSubMenu);
menu.addAction(findPlaceAct);
menu.addSeparator();
menu.addSeparator();
*/ QMenu copySubMenu(tr("Copy"), this);
copySubMenu.addAction(copyMouseLatLonToClipAct);
menu.addAction(showSafeAreaAct); copySubMenu.addAction(copyMouseLatToClipAct);
QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); copySubMenu.addAction(copyMouseLonToClipAct);
for (int i = 0; i < safeAreaAct.count(); i++) menu.addMenu(&copySubMenu);
safeAreaSubMenu.addAction(safeAreaAct.at(i));
menu.addMenu(&safeAreaSubMenu); menu.addSeparator();
menu.addSeparator(); /*
menu.addAction(findPlaceAct);
menu.addAction(showCompassAct);
menu.addSeparator();
menu.addAction(showDiagnostics); */
menu.addSeparator()->setText(tr("Zoom")); menu.addAction(showSafeAreaAct);
QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this);
menu.addAction(zoomInAct); for (int i = 0; i < safeAreaAct.count(); i++)
menu.addAction(zoomOutAct); safeAreaSubMenu.addAction(safeAreaAct.at(i));
menu.addMenu(&safeAreaSubMenu);
QMenu zoomSubMenu(tr("&Zoom ") + "(" + QString::number(m_map->ZoomTotal()) + ")", this);
for (int i = 0; i < zoomAct.count(); i++) menu.addSeparator();
zoomSubMenu.addAction(zoomAct.at(i));
menu.addMenu(&zoomSubMenu); menu.addAction(showCompassAct);
menu.addSeparator(); menu.addAction(showDiagnostics);
menu.addAction(goMouseClickAct); menu.addSeparator()->setText(tr("Zoom"));
menu.addSeparator()->setText(tr("HOME")); menu.addAction(zoomInAct);
menu.addAction(zoomOutAct);
menu.addAction(setHomeAct);
menu.addAction(showHomeAct); QMenu zoomSubMenu(tr("&Zoom ") + "(" + QString::number(m_map->ZoomTotal()) + ")", this);
menu.addAction(goHomeAct); for (int i = 0; i < zoomAct.count(); i++)
zoomSubMenu.addAction(zoomAct.at(i));
// **** menu.addMenu(&zoomSubMenu);
// uav trails
menu.addSeparator();
menu.addSeparator()->setText(tr("UAV Trail"));
menu.addAction(goMouseClickAct);
QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this);
for (int i = 0; i < uavTrailTypeAct.count(); i++) menu.addSeparator()->setText(tr("HOME"));
uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i));
menu.addMenu(&uavTrailTypeSubMenu); menu.addAction(setHomeAct);
menu.addAction(showHomeAct);
QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this); menu.addAction(goHomeAct);
for (int i = 0; i < uavTrailTimeAct.count(); i++)
uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i)); // ****
menu.addMenu(&uavTrailTimeSubMenu); // uav trails
QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this); menu.addSeparator()->setText(tr("UAV Trail"));
for (int i = 0; i < uavTrailDistanceAct.count(); i++)
uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i)); QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this);
menu.addMenu(&uavTrailDistanceSubMenu); for (int i = 0; i < uavTrailTypeAct.count(); i++)
uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i));
menu.addAction(showTrailAct); menu.addMenu(&uavTrailTypeSubMenu);
menu.addAction(showTrailLineAct); QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this);
for (int i = 0; i < uavTrailTimeAct.count(); i++)
menu.addAction(clearUAVtrailAct); uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i));
menu.addMenu(&uavTrailTimeSubMenu);
// ****
QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this);
menu.addSeparator()->setText(tr("UAV")); for (int i = 0; i < uavTrailDistanceAct.count(); i++)
uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i));
menu.addAction(showUAVAct); menu.addMenu(&uavTrailDistanceSubMenu);
menu.addAction(followUAVpositionAct);
menu.addAction(followUAVheadingAct); menu.addAction(showTrailAct);
menu.addAction(goUAVAct);
menu.addAction(showTrailLineAct);
// *********
menu.addAction(clearUAVtrailAct);
switch (m_map_mode)
{ // ****
case Normal_MapMode:
// only show the waypoint stuff if not in 'magic waypoint' mode menu.addSeparator()->setText(tr("UAV"));
/*
menu.addSeparator()->setText(tr("Waypoints")); menu.addAction(showUAVAct);
menu.addAction(followUAVpositionAct);
menu.addAction(wayPointEditorAct); menu.addAction(followUAVheadingAct);
menu.addAction(addWayPointAct); menu.addAction(goUAVAct);
if (m_mouse_waypoint) // *********
{ // we have a waypoint under the mouse
menu.addAction(editWayPointAct); switch (m_map_mode)
{
lockWayPointAct->setChecked(waypoint_locked); case Normal_MapMode:
menu.addAction(lockWayPointAct); // only show the waypoint stuff if not in 'magic waypoint' mode
/*
if (!waypoint_locked) menu.addSeparator()->setText(tr("Waypoints"));
menu.addAction(deleteWayPointAct);
} menu.addAction(wayPointEditorAct);
menu.addAction(addWayPointAct);
m_waypoint_list_mutex.lock();
if (m_waypoint_list.count() > 0) if (m_mouse_waypoint)
menu.addAction(clearWayPointsAct); // we have waypoints { // we have a waypoint under the mouse
m_waypoint_list_mutex.unlock(); menu.addAction(editWayPointAct);
*/
lockWayPointAct->setChecked(waypoint_locked);
break; menu.addAction(lockWayPointAct);
case MagicWaypoint_MapMode: if (!waypoint_locked)
menu.addSeparator()->setText(tr("Waypoints")); menu.addAction(deleteWayPointAct);
menu.addAction(homeMagicWaypointAct); }
break;
} m_waypoint_list_mutex.lock();
if (m_waypoint_list.count() > 0)
// ********* menu.addAction(clearWayPointsAct); // we have waypoints
m_waypoint_list_mutex.unlock();
menu.addSeparator(); */
menu.addAction(closeAct2); break;
menu.exec(event->globalPos()); // popup the menu case MagicWaypoint_MapMode:
menu.addSeparator()->setText(tr("Waypoints"));
// **************** menu.addAction(homeMagicWaypointAct);
} break;
}
void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event)
{ // *********
qDebug() << "opmap: keyPressEvent, key =" << event->key() << endl;
menu.addSeparator();
switch (event->key())
{ menu.addAction(closeAct2);
case Qt::Key_Escape:
break; menu.exec(event->globalPos()); // popup the menu
case Qt::Key_F1: // ****************
break; }
case Qt::Key_F2: void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event)
break; {
qDebug() << "opmap: keyPressEvent, key =" << event->key() << endl;
case Qt::Key_Up:
break; switch (event->key())
{
case Qt::Key_Down: case Qt::Key_Escape:
break; break;
case Qt::Key_Left: case Qt::Key_F1:
break; break;
case Qt::Key_Right: case Qt::Key_F2:
break; break;
case Qt::Key_PageUp: case Qt::Key_Up:
break; break;
case Qt::Key_PageDown: case Qt::Key_Down:
break; break;
}
} case Qt::Key_Left:
break;
// *************************************************************************************
// timer signals case Qt::Key_Right:
break;
/** case Qt::Key_PageUp:
Updates the UAV position on the map. It is called every 200ms break;
by a timer.
case Qt::Key_PageDown:
TODO: consider updating upon object update, not timer. break;
*/ }
void OPMapGadgetWidget::updatePosition() }
{
if (!m_widget || !m_map) // *************************************************************************************
return; // timer signals
QMutexLocker locker(&m_map_mutex); /**
//Pip I'm sorry, I know this was here with a purpose vvv Updates the UAV position on the map. It is called every 200ms
//if (!telemetry_connected) by a timer.
// return;
TODO: consider updating upon object update, not timer.
double latitude;
double longitude; from Pip: No don't update on object update - had reports that peoples PC's can't cope with high update rates - have had to allow user to set map update from 100ms to 5 seconds (depending on their PC's graphics processing ability), so this needs to be kept on a timer.
double altitude; */
void OPMapGadgetWidget::updatePosition()
// get current UAV position {
if (!getUAVPosition(latitude, longitude, altitude)) double uav_latitude, uav_longitude, uav_altitude, uav_yaw;
return; double gps_latitude, gps_longitude, gps_altitude, gps_heading;
// get current UAV heading internals::PointLatLng uav_pos;
float yaw = getUAV_Yaw(); internals::PointLatLng gps_pos;
internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position if (!m_widget || !m_map)
float uav_heading_degrees = yaw; // current UAV heading return;
float uav_altitude_meters = altitude; // current UAV height
float uav_ground_speed_meters_per_second = 0; //data.Groundspeed; // current UAV ground speed QMutexLocker locker(&m_map_mutex);
// Pip I'm sorry, I know this was here with a purpose vvv
// display the UAV lat/lon position // from Pip: let you off :)
QString str = //if (!telemetry_connected)
"lat: " + QString::number(uav_pos.Lat(), 'f', 7) + // return;
" lon: " + QString::number(uav_pos.Lng(), 'f', 7) +
" " + QString::number(uav_heading_degrees, 'f', 1) + "deg" + // *************
" " + QString::number(uav_altitude_meters, 'f', 1) + "m" + // get the current UAV details
" " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s";
m_widget->labelUAVPos->setText(str); // get current UAV position
if (!getUAVPosition(uav_latitude, uav_longitude, uav_altitude))
m_map->UAV->SetUAVPos(uav_pos, uav_altitude_meters); // set the maps UAV position return;
// qDebug()<<"UAVPOSITION"<<uav_pos.ToString();
m_map->UAV->SetUAVHeading(uav_heading_degrees); // set the maps UAV heading // get current UAV heading
uav_yaw = getUAV_Yaw();
if (!getGPSPosition(latitude, longitude, altitude))
return; uav_pos = internals::PointLatLng(uav_latitude, uav_longitude);
uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position // *************
m_map->GPS->SetUAVPos(uav_pos, uav_altitude_meters); // set the maps UAV position // get the current GPS details
m_map->GPS->SetUAVHeading(uav_heading_degrees); // set the maps UAV heading
} // get current GPS position
if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude))
/** return;
Update plugin behaviour based on mouse position; Called every few ms by a
timer. // get current GPS heading
*/ // gps_heading = getGPS_Heading();
void OPMapGadgetWidget::updateMousePos() gps_heading = 0;
{
if (!m_widget || !m_map) gps_pos = internals::PointLatLng(gps_latitude, gps_longitude);
return;
// *************
QMutexLocker locker(&m_map_mutex); // display the UAV position
QPoint p = m_map->mapFromGlobal(QCursor::pos()); QString str =
internals::PointLatLng lat_lon = m_map->GetFromLocalToLatLng(p); // fetch the current lat/lon mouse position "lat: " + QString::number(uav_pos.Lat(), 'f', 7) +
" lon: " + QString::number(uav_pos.Lng(), 'f', 7) +
if (!m_map->contentsRect().contains(p)) " " + QString::number(uav_yaw, 'f', 1) + "deg" +
return; // the mouse is not on the map " " + QString::number(uav_altitude, 'f', 1) + "m";
// " " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s";
// internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position m_widget->labelUAVPos->setText(str);
QGraphicsItem *item = m_map->itemAt(p); // *************
// set the UAV icon position on the map
// find out if we are over the home position
mapcontrol::HomeItem *home = qgraphicsitem_cast<mapcontrol::HomeItem *>(item); m_map->UAV->SetUAVPos(uav_pos, uav_altitude); // set the maps UAV position
// qDebug()<<"UAVPOSITION"<<uav_pos.ToString();
// find out if we are over the UAV m_map->UAV->SetUAVHeading(uav_yaw); // set the maps UAV heading
mapcontrol::UAVItem *uav = qgraphicsitem_cast<mapcontrol::UAVItem *>(item);
// *************
// find out if we have a waypoint under the mouse cursor // set the GPS icon position on the map
mapcontrol::WayPointItem *wp = qgraphicsitem_cast<mapcontrol::WayPointItem *>(item);
m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position
if (mouse_lat_lon == lat_lon) m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading
return; // the mouse has not moved
// *************
mouse_lat_lon = lat_lon; // yes it has! }
internals::PointLatLng home_lat_lon = m_map->Home->Coord(); /**
Update plugin behaviour based on mouse position; Called every few ms by a
QString s = QString::number(mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(mouse_lat_lon.Lng(), 'f', 7); timer.
if (wp) */
{ void OPMapGadgetWidget::updateMousePos()
s += " wp[" + QString::number(wp->Number()) + "]"; {
if (!m_widget || !m_map)
double dist = distance(home_lat_lon, wp->Coord()); return;
double bear = bearing(home_lat_lon, wp->Coord());
s += " " + QString::number(dist * 1000, 'f', 1) + "m"; QMutexLocker locker(&m_map_mutex);
s += " " + QString::number(bear, 'f', 1) + "deg";
} QPoint p = m_map->mapFromGlobal(QCursor::pos());
else internals::PointLatLng lat_lon = m_map->GetFromLocalToLatLng(p); // fetch the current lat/lon mouse position
if (home)
{ if (!m_map->contentsRect().contains(p))
s += " home"; return; // the mouse is not on the map
double dist = distance(home_lat_lon, mouse_lat_lon); // internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position
double bear = bearing(home_lat_lon, mouse_lat_lon);
s += " " + QString::number(dist * 1000, 'f', 1) + "m"; QGraphicsItem *item = m_map->itemAt(p);
s += " " + QString::number(bear, 'f', 1) + "deg";
} // find out if we are over the home position
else mapcontrol::HomeItem *home = qgraphicsitem_cast<mapcontrol::HomeItem *>(item);
if (uav)
{ // find out if we are over the UAV
s += " uav"; mapcontrol::UAVItem *uav = qgraphicsitem_cast<mapcontrol::UAVItem *>(item);
double latitude; // find out if we have a waypoint under the mouse cursor
double longitude; mapcontrol::WayPointItem *wp = qgraphicsitem_cast<mapcontrol::WayPointItem *>(item);
double altitude;
if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position if (m_mouse_lat_lon == lat_lon)
{ return; // the mouse has not moved
internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude);
m_mouse_lat_lon = lat_lon; // yes it has!
// double dist = distance(home_lat_lon, uav_pos);
// double bear = bearing(home_lat_lon, uav_pos); internals::PointLatLng home_lat_lon = m_map->Home->Coord();
// s += " " + QString::number(dist * 1000, 'f', 1) + "m";
// s += " " + QString::number(bear, 'f', 1) + "deg"; QString s = QString::number(m_mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_mouse_lat_lon.Lng(), 'f', 7);
} if (wp)
} {
m_widget->labelMousePos->setText(s); s += " wp[" + QString::number(wp->Number()) + "]";
}
double dist = distance(home_lat_lon, wp->Coord());
// ************************************************************************************* double bear = bearing(home_lat_lon, wp->Coord());
// map signals s += " " + QString::number(dist * 1000, 'f', 1) + "m";
s += " " + QString::number(bear, 'f', 1) + "deg";
}
/** else
Update the Plugin UI to reflect a change in zoom level if (home)
*/ {
void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) s += " home";
{
if (!m_widget || !m_map) double dist = distance(home_lat_lon, m_mouse_lat_lon);
return; double bear = bearing(home_lat_lon, m_mouse_lat_lon);
s += " " + QString::number(dist * 1000, 'f', 1) + "m";
QString s = "tot:" + QString::number(zoomt, 'f', 1) + " rea:" + QString::number(zoom, 'f', 1) + " dig:" + QString::number(zoomd, 'f', 1); s += " " + QString::number(bear, 'f', 1) + "deg";
m_widget->labelMapZoom->setText(s); }
else
int i_zoom = (int)(zoomt + 0.5); if (uav)
{
if (i_zoom < min_zoom) i_zoom = min_zoom; s += " uav";
else
if (i_zoom > max_zoom) i_zoom = max_zoom; double latitude;
double longitude;
if (m_widget->horizontalSliderZoom->value() != i_zoom) double altitude;
m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position
{
int index0_zoom = i_zoom - min_zoom; // zoom level starting at index level '0' internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude);
if (index0_zoom < zoomAct.count())
zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level // double dist = distance(home_lat_lon, uav_pos);
} // double bear = bearing(home_lat_lon, uav_pos);
// s += " " + QString::number(dist * 1000, 'f', 1) + "m";
void OPMapGadgetWidget::OnMapDrag() // s += " " + QString::number(bear, 'f', 1) + "deg";
{ }
} }
m_widget->labelMousePos->setText(s);
void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) }
{
if (!m_widget || !m_map) // *************************************************************************************
return; // map signals
QString coord_str = QString::number(point.Lat(), 'f', 7) + " " + QString::number(point.Lng(), 'f', 7) + " ";
m_widget->labelMapPos->setText(coord_str); /**
} Update the Plugin UI to reflect a change in zoom level
*/
/** void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd)
Update the progress bar while there are still tiles to load {
*/ if (!m_widget || !m_map)
void OPMapGadgetWidget::OnTilesStillToLoad(int number) return;
{
if (!m_widget || !m_map) QString s = "tot:" + QString::number(zoomt, 'f', 1) + " rea:" + QString::number(zoom, 'f', 1) + " dig:" + QString::number(zoomd, 'f', 1);
return; m_widget->labelMapZoom->setText(s);
// if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) int i_zoom = (int)(zoomt + 0.5);
// m_widget->progressBarMap->setMaximum(number);
if (i_zoom < m_min_zoom) i_zoom = m_min_zoom;
if (m_widget->progressBarMap->maximum() < number) else
m_widget->progressBarMap->setMaximum(number); if (i_zoom > m_max_zoom) i_zoom = m_max_zoom;
m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar if (m_widget->horizontalSliderZoom->value() != i_zoom)
m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position
// m_widget->labelNumTilesToLoad->setText(QString::number(number));
int index0_zoom = i_zoom - m_min_zoom; // zoom level starting at index level '0'
prev_tile_number = number; if (index0_zoom < zoomAct.count())
} zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level
}
/**
Show the progress bar as soon as the map lib starts downloading void OPMapGadgetWidget::OnMapDrag()
*/ {
void OPMapGadgetWidget::OnTileLoadStart() }
{
if (!m_widget || !m_map) void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point)
return; {
if (!m_widget || !m_map)
m_widget->progressBarMap->setVisible(true); return;
}
QString coord_str = QString::number(point.Lat(), 'f', 7) + " " + QString::number(point.Lng(), 'f', 7) + " ";
/** m_widget->labelMapPos->setText(coord_str);
Hide the progress bar once the map lib has finished downloading }
TODO: somehow this gets called before tile load is actually complete? /**
*/ Update the progress bar while there are still tiles to load
*/
void OPMapGadgetWidget::OnTileLoadComplete() void OPMapGadgetWidget::OnTilesStillToLoad(int number)
{ {
if (!m_widget || !m_map) if (!m_widget || !m_map)
return; return;
m_widget->progressBarMap->setVisible(false); // if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number)
} // m_widget->progressBarMap->setMaximum(number);
void OPMapGadgetWidget::OnMapZoomChanged() if (m_widget->progressBarMap->maximum() < number)
{ m_widget->progressBarMap->setMaximum(number);
}
m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar
void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type)
{ // m_widget->labelNumTilesToLoad->setText(QString::number(number));
Q_UNUSED(type);
} m_prev_tile_number = number;
}
void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos)
{ /**
Q_UNUSED(zoom); Show the progress bar as soon as the map lib starts downloading
Q_UNUSED(pos); */
} void OPMapGadgetWidget::OnTileLoadStart()
{
void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumber, WayPointItem *waypoint) if (!m_widget || !m_map)
{ return;
Q_UNUSED(oldnumber);
Q_UNUSED(newnumber); m_widget->progressBarMap->setVisible(true);
Q_UNUSED(waypoint); }
}
/**
void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) Hide the progress bar once the map lib has finished downloading
{
// qDebug("opmap: WPValuesChanged"); TODO: somehow this gets called before tile load is actually complete?
*/
switch (m_map_mode)
{ void OPMapGadgetWidget::OnTileLoadComplete()
case Normal_MapMode: {
m_waypoint_list_mutex.lock(); if (!m_widget || !m_map)
foreach (t_waypoint *wp, m_waypoint_list) return;
{ // search for the waypoint in our own waypoint list and update it
if (!wp) continue; m_widget->progressBarMap->setVisible(false);
if (!wp->map_wp_item) continue; }
if (wp->map_wp_item != waypoint) continue;
// found the waypoint in our list void OPMapGadgetWidget::OnMapZoomChanged()
wp->coord = waypoint->Coord(); {
wp->altitude = waypoint->Altitude(); }
wp->description = waypoint->Description();
break; void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type)
} {
m_waypoint_list_mutex.unlock(); Q_UNUSED(type);
break; }
case MagicWaypoint_MapMode: void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos)
// update our copy of the magic waypoint {
if (magic_waypoint.map_wp_item && magic_waypoint.map_wp_item == waypoint) Q_UNUSED(zoom);
{ Q_UNUSED(pos);
magic_waypoint.coord = waypoint->Coord(); }
magic_waypoint.altitude = waypoint->Altitude();
magic_waypoint.description = waypoint->Description(); void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumber, WayPointItem *waypoint)
{
// move the UAV to the magic waypoint position Q_UNUSED(oldnumber);
// moveToMagicWaypointPosition(); Q_UNUSED(newnumber);
} Q_UNUSED(waypoint);
break; }
}
void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint)
} {
// qDebug("opmap: WPValuesChanged");
/**
TODO: slot to do something upon Waypoint insertion switch (m_map_mode)
*/ {
void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint) case Normal_MapMode:
{ m_waypoint_list_mutex.lock();
Q_UNUSED(number); foreach (t_waypoint *wp, m_waypoint_list)
Q_UNUSED(waypoint); { // search for the waypoint in our own waypoint list and update it
} if (!wp) continue;
if (!wp->map_wp_item) continue;
/** if (wp->map_wp_item != waypoint) continue;
TODO: slot to do something upon Waypoint deletion // found the waypoint in our list
*/ wp->coord = waypoint->Coord();
void OPMapGadgetWidget::WPDeleted(int const &number) wp->altitude = waypoint->Altitude();
{ wp->description = waypoint->Description();
Q_UNUSED(number); break;
} }
m_waypoint_list_mutex.unlock();
break;
void OPMapGadgetWidget::on_toolButtonZoomP_clicked()
{ case MagicWaypoint_MapMode:
QMutexLocker locker(&m_map_mutex); // update our copy of the magic waypoint
zoomIn(); if (m_magic_waypoint.map_wp_item && m_magic_waypoint.map_wp_item == waypoint)
} {
m_magic_waypoint.coord = waypoint->Coord();
void OPMapGadgetWidget::on_toolButtonZoomM_clicked() m_magic_waypoint.altitude = waypoint->Altitude();
{ m_magic_waypoint.description = waypoint->Description();
QMutexLocker locker(&m_map_mutex);
zoomOut(); // move the UAV to the magic waypoint position
} // moveToMagicWaypointPosition();
}
void OPMapGadgetWidget::on_toolButtonMapHome_clicked() break;
{ }
QMutexLocker locker(&m_map_mutex);
goHome(); }
}
/**
void OPMapGadgetWidget::on_toolButtonMapUAV_clicked() TODO: slot to do something upon Waypoint insertion
{ */
if (!m_widget || !m_map) void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint)
return; {
Q_UNUSED(number);
QMutexLocker locker(&m_map_mutex); Q_UNUSED(waypoint);
}
followUAVpositionAct->toggle();
} /**
TODO: slot to do something upon Waypoint deletion
void OPMapGadgetWidget::on_toolButtonMapUAVheading_clicked() */
{ void OPMapGadgetWidget::WPDeleted(int const &number)
if (!m_widget || !m_map) {
return; Q_UNUSED(number);
}
followUAVheadingAct->toggle();
}
void OPMapGadgetWidget::on_toolButtonZoomP_clicked()
void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position) {
{ QMutexLocker locker(&m_map_mutex);
if (!m_widget || !m_map) zoomIn();
return; }
QMutexLocker locker(&m_map_mutex); void OPMapGadgetWidget::on_toolButtonZoomM_clicked()
{
setZoom(position); QMutexLocker locker(&m_map_mutex);
} zoomOut();
}
void OPMapGadgetWidget::on_toolButtonNormalMapMode_clicked() void OPMapGadgetWidget::on_toolButtonMapHome_clicked()
{ {
setMapMode(Normal_MapMode); QMutexLocker locker(&m_map_mutex);
} goHome();
}
void OPMapGadgetWidget::on_toolButtonMagicWaypointMapMode_clicked()
{ void OPMapGadgetWidget::on_toolButtonMapUAV_clicked()
setMapMode(MagicWaypoint_MapMode); {
} if (!m_widget || !m_map)
return;
void OPMapGadgetWidget::on_toolButtonHomeWaypoint_clicked()
{ QMutexLocker locker(&m_map_mutex);
homeMagicWaypoint();
} followUAVpositionAct->toggle();
}
void OPMapGadgetWidget::on_toolButtonMoveToWP_clicked()
{ void OPMapGadgetWidget::on_toolButtonMapUAVheading_clicked()
moveToMagicWaypointPosition(); {
} if (!m_widget || !m_map)
return;
// *************************************************************************************
// public slots followUAVheadingAct->toggle();
}
void OPMapGadgetWidget::onTelemetryConnect()
{ void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position)
telemetry_connected = true; {
if (!m_widget || !m_map)
if (!obum) return; return;
bool set; QMutexLocker locker(&m_map_mutex);
double LLA[3];
setZoom(position);
// *********************** }
// fetch the home location
if (obum->getHomeLocation(set, LLA) < 0) void OPMapGadgetWidget::on_toolButtonNormalMapMode_clicked()
return; // error {
setMapMode(Normal_MapMode);
setHome(internals::PointLatLng(LLA[0], LLA[1])); }
if (m_map) void OPMapGadgetWidget::on_toolButtonMagicWaypointMapMode_clicked()
m_map->SetCurrentPosition(home_position.coord); // set the map position {
setMapMode(MagicWaypoint_MapMode);
// *********************** }
}
void OPMapGadgetWidget::on_toolButtonHomeWaypoint_clicked()
void OPMapGadgetWidget::onTelemetryDisconnect() {
{ homeMagicWaypoint();
telemetry_connected = false; }
}
void OPMapGadgetWidget::on_toolButtonMoveToWP_clicked()
// Updates the Home position icon whenever the HomePosition object is updated {
void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) moveToMagicWaypointPosition();
{ }
if (!hp)
return; // *************************************************************************************
// public slots
double lat = hp->getField("Latitude")->getDouble() * 1e-7;
double lon = hp->getField("Longitude")->getDouble() * 1e-7; void OPMapGadgetWidget::onTelemetryConnect()
setHome(internals::PointLatLng(lat, lon)); {
} m_telemetry_connected = true;
// ************************************************************************************* if (!obum) return;
// public functions
bool set;
/** double LLA[3];
Sets the home position on the map widget
*/ // ***********************
void OPMapGadgetWidget::setHome(QPointF pos) // fetch the home location
{
if (!m_widget || !m_map) if (obum->getHomeLocation(set, LLA) < 0)
return; return; // error
double latitude = pos.x(); setHome(internals::PointLatLng(LLA[0], LLA[1]));
double longitude = pos.y();
if (m_map)
if (latitude > 90) latitude = 90; m_map->SetCurrentPosition(m_home_position.coord); // set the map position
else
if (latitude < -90) latitude = -90; // ***********************
}
if (longitude != longitude) longitude = 0; // nan detection
else void OPMapGadgetWidget::onTelemetryDisconnect()
if (longitude > 180) longitude = 180; {
else m_telemetry_connected = false;
if (longitude < -180) longitude = -180; }
setHome(internals::PointLatLng(latitude, longitude)); // Updates the Home position icon whenever the HomePosition object is updated
} void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp)
{
/** if (!hp)
Sets the home position on the map widget return;
*/
void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) double lat = hp->getField("Latitude")->getDouble() * 1e-7;
{ double lon = hp->getField("Longitude")->getDouble() * 1e-7;
if (!m_widget || !m_map) setHome(internals::PointLatLng(lat, lon));
return; }
if (pos_lat_lon.Lat() != pos_lat_lon.Lat() || pos_lat_lon.Lng() != pos_lat_lon.Lng()) // *************************************************************************************
return;; // nan prevention // public functions
double latitude = pos_lat_lon.Lat(); /**
double longitude = pos_lat_lon.Lng(); Sets the home position on the map widget
*/
if (latitude != latitude) latitude = 0; // nan detection void OPMapGadgetWidget::setHome(QPointF pos)
else {
if (latitude > 90) latitude = 90; if (!m_widget || !m_map)
else return;
if (latitude < -90) latitude = -90;
double latitude = pos.x();
if (longitude != longitude) longitude = 0; // nan detection double longitude = pos.y();
else
if (longitude > 180) longitude = 180; if (latitude > 90) latitude = 90;
else else
if (longitude < -180) longitude = -180; if (latitude < -90) latitude = -90;
// ********* if (longitude != longitude) longitude = 0; // nan detection
else
home_position.coord = internals::PointLatLng(latitude, longitude); if (longitude > 180) longitude = 180;
else
m_map->Home->SetCoord(home_position.coord); if (longitude < -180) longitude = -180;
m_map->Home->RefreshPos();
setHome(internals::PointLatLng(latitude, longitude));
// move the magic waypoint to keep it within the safe area boundry }
keepMagicWaypointWithInSafeArea();
} /**
Sets the home position on the map widget
*/
/** void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon)
Centers the map over the home position {
*/ if (!m_widget || !m_map)
void OPMapGadgetWidget::goHome() return;
{
if (!m_widget || !m_map) if (pos_lat_lon.Lat() != pos_lat_lon.Lat() || pos_lat_lon.Lng() != pos_lat_lon.Lng())
return; return;; // nan prevention
followUAVpositionAct->setChecked(false); double latitude = pos_lat_lon.Lat();
double longitude = pos_lat_lon.Lng();
internals::PointLatLng home_pos = home_position.coord; // get the home location
m_map->SetCurrentPosition(home_pos); // center the map onto the home location if (latitude != latitude) latitude = 0; // nan detection
} else
if (latitude > 90) latitude = 90;
else
void OPMapGadgetWidget::zoomIn() if (latitude < -90) latitude = -90;
{
if (!m_widget || !m_map) if (longitude != longitude) longitude = 0; // nan detection
return; else
if (longitude > 180) longitude = 180;
int zoom = m_map->ZoomTotal() + 1; else
if (longitude < -180) longitude = -180;
if (zoom < min_zoom) zoom = min_zoom;
else // *********
if (zoom > max_zoom) zoom = max_zoom;
m_home_position.coord = internals::PointLatLng(latitude, longitude);
m_map->SetZoom(zoom);
} m_map->Home->SetCoord(m_home_position.coord);
m_map->Home->RefreshPos();
void OPMapGadgetWidget::zoomOut()
{ // move the magic waypoint to keep it within the safe area boundry
if (!m_widget || !m_map) keepMagicWaypointWithInSafeArea();
return; }
int zoom = m_map->ZoomTotal() - 1;
/**
if (zoom < min_zoom) zoom = min_zoom; Centers the map over the home position
else */
if (zoom > max_zoom) zoom = max_zoom; void OPMapGadgetWidget::goHome()
{
m_map->SetZoom(zoom); if (!m_widget || !m_map)
} return;
void OPMapGadgetWidget::setZoom(int zoom) followUAVpositionAct->setChecked(false);
{
if (!m_widget || !m_map) internals::PointLatLng home_pos = m_home_position.coord; // get the home location
return; m_map->SetCurrentPosition(home_pos); // center the map onto the home location
}
if (zoom < min_zoom) zoom = min_zoom;
else
if (zoom > max_zoom) zoom = max_zoom; void OPMapGadgetWidget::zoomIn()
{
internals::MouseWheelZoomType::Types zoom_type = m_map->GetMouseWheelZoomType(); if (!m_widget || !m_map)
m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::ViewCenter); return;
m_map->SetZoom(zoom); int zoom = m_map->ZoomTotal() + 1;
m_map->SetMouseWheelZoomType(zoom_type); if (zoom < m_min_zoom) zoom = m_min_zoom;
} else
if (zoom > m_max_zoom) zoom = m_max_zoom;
void OPMapGadgetWidget::setPosition(QPointF pos)
{ m_map->SetZoom(zoom);
if (!m_widget || !m_map) }
return;
void OPMapGadgetWidget::zoomOut()
double latitude = pos.y(); {
double longitude = pos.x(); if (!m_widget || !m_map)
return;
if (latitude != latitude || longitude != longitude)
return; // nan prevention int zoom = m_map->ZoomTotal() - 1;
if (latitude > 90) latitude = 90; if (zoom < m_min_zoom) zoom = m_min_zoom;
else else
if (latitude < -90) latitude = -90; if (zoom > m_max_zoom) zoom = m_max_zoom;
if (longitude > 180) longitude = 180; m_map->SetZoom(zoom);
else }
if (longitude < -180) longitude = -180;
void OPMapGadgetWidget::setMaxUpdateRate(int update_rate)
m_map->SetCurrentPosition(internals::PointLatLng(latitude, longitude)); {
} if (!m_widget || !m_map)
return;
void OPMapGadgetWidget::setMapProvider(QString provider)
{ int list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]);
if (!m_widget || !m_map) int min_rate = max_update_rate_list[0];
return; int max_rate = max_update_rate_list[list_size - 1];
m_map->SetMapType(mapcontrol::Helper::MapTypeFromString(provider)); if (update_rate < min_rate) update_rate = min_rate;
} else
if (update_rate > max_rate) update_rate = max_rate;
void OPMapGadgetWidget::setAccessMode(QString accessMode)
{ m_maxUpdateRate = update_rate;
if (!m_widget || !m_map)
return; if (m_updateTimer)
m_updateTimer->setInterval(m_maxUpdateRate);
m_map->configuration->SetAccessMode(mapcontrol::Helper::AccessModeFromString(accessMode));
} // if (m_statusUpdateTimer)
// m_statusUpdateTimer->setInterval(m_maxUpdateRate);
void OPMapGadgetWidget::setUseOpenGL(bool useOpenGL) }
{
if (!m_widget || !m_map) void OPMapGadgetWidget::setZoom(int zoom)
return; {
if (!m_widget || !m_map)
m_map->SetUseOpenGL(useOpenGL); return;
}
if (zoom < m_min_zoom) zoom = m_min_zoom;
void OPMapGadgetWidget::setShowTileGridLines(bool showTileGridLines) else
{ if (zoom > m_max_zoom) zoom = m_max_zoom;
if (!m_widget || !m_map)
return; internals::MouseWheelZoomType::Types zoom_type = m_map->GetMouseWheelZoomType();
m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::ViewCenter);
m_map->SetShowTileGridLines(showTileGridLines);
} m_map->SetZoom(zoom);
void OPMapGadgetWidget::setUseMemoryCache(bool useMemoryCache) m_map->SetMouseWheelZoomType(zoom_type);
{ }
if (!m_widget || !m_map)
return; void OPMapGadgetWidget::setPosition(QPointF pos)
{
m_map->configuration->SetUseMemoryCache(useMemoryCache); if (!m_widget || !m_map)
} return;
void OPMapGadgetWidget::setCacheLocation(QString cacheLocation) double latitude = pos.y();
{ double longitude = pos.x();
if (!m_widget || !m_map)
return; if (latitude != latitude || longitude != longitude)
return; // nan prevention
cacheLocation = cacheLocation.simplified(); // remove any surrounding spaces
if (latitude > 90) latitude = 90;
if (cacheLocation.isEmpty()) return; else
if (latitude < -90) latitude = -90;
// #if defined(Q_WS_WIN)
// if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; if (longitude > 180) longitude = 180;
// #elif defined(Q_WS_X11) else
if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); if (longitude < -180) longitude = -180;
// #elif defined(Q_WS_MAC)
// if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); m_map->SetCurrentPosition(internals::PointLatLng(latitude, longitude));
// #endif }
QDir dir; void OPMapGadgetWidget::setMapProvider(QString provider)
if (!dir.exists(cacheLocation)) {
if (!dir.mkpath(cacheLocation)) if (!m_widget || !m_map)
return; return;
// qDebug() << "opmap: map cache dir: " << cacheLocation; m_map->SetMapType(mapcontrol::Helper::MapTypeFromString(provider));
}
m_map->configuration->SetCacheLocation(cacheLocation);
} void OPMapGadgetWidget::setAccessMode(QString accessMode)
{
void OPMapGadgetWidget::setMapMode(opMapModeType mode) if (!m_widget || !m_map)
{ return;
if (!m_widget || !m_map)
return; m_map->configuration->SetAccessMode(mapcontrol::Helper::AccessModeFromString(accessMode));
}
if (mode != Normal_MapMode && mode != MagicWaypoint_MapMode)
mode = Normal_MapMode; // fix error void OPMapGadgetWidget::setUseOpenGL(bool useOpenGL)
{
if (m_map_mode == mode) if (!m_widget || !m_map)
{ // no change in map mode return;
switch (mode)
{ // make sure the UI buttons are set correctly m_map->SetUseOpenGL(useOpenGL);
case Normal_MapMode: }
m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
m_widget->toolButtonNormalMapMode->setChecked(true); void OPMapGadgetWidget::setShowTileGridLines(bool showTileGridLines)
break; {
case MagicWaypoint_MapMode: if (!m_widget || !m_map)
m_widget->toolButtonNormalMapMode->setChecked(false); return;
m_widget->toolButtonMagicWaypointMapMode->setChecked(true);
break; m_map->SetShowTileGridLines(showTileGridLines);
} }
return;
} void OPMapGadgetWidget::setUseMemoryCache(bool useMemoryCache)
{
switch (mode) if (!m_widget || !m_map)
{ return;
case Normal_MapMode:
m_map_mode = Normal_MapMode; m_map->configuration->SetUseMemoryCache(useMemoryCache);
}
m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
m_widget->toolButtonNormalMapMode->setChecked(true); void OPMapGadgetWidget::setCacheLocation(QString cacheLocation)
{
hideMagicWaypointControls(); if (!m_widget || !m_map)
return;
// delete the magic waypoint from the map
if (magic_waypoint.map_wp_item) cacheLocation = cacheLocation.simplified(); // remove any surrounding spaces
{
magic_waypoint.coord = magic_waypoint.map_wp_item->Coord(); if (cacheLocation.isEmpty()) return;
magic_waypoint.altitude = magic_waypoint.map_wp_item->Altitude();
magic_waypoint.description = magic_waypoint.map_wp_item->Description(); // #if defined(Q_WS_WIN)
magic_waypoint.map_wp_item = NULL; // if (!cacheLocation.endsWith('\\')) cacheLocation += '\\';
} // #elif defined(Q_WS_X11)
m_map->WPDeleteAll(); if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator();
// #elif defined(Q_WS_MAC)
// restore the normal waypoints on the map // if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator();
m_waypoint_list_mutex.lock(); // #endif
foreach (t_waypoint *wp, m_waypoint_list)
{ QDir dir;
if (!wp) continue; if (!dir.exists(cacheLocation))
wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); if (!dir.mkpath(cacheLocation))
if (!wp->map_wp_item) continue; return;
wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number());
wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); // qDebug() << "opmap: map cache dir: " << cacheLocation;
if (!wp->locked)
wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); m_map->configuration->SetCacheLocation(cacheLocation);
else }
wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png"));
wp->map_wp_item->update(); void OPMapGadgetWidget::setMapMode(opMapModeType mode)
} {
m_waypoint_list_mutex.unlock(); if (!m_widget || !m_map)
return;
break;
if (mode != Normal_MapMode && mode != MagicWaypoint_MapMode)
case MagicWaypoint_MapMode: mode = Normal_MapMode; // fix error
m_map_mode = MagicWaypoint_MapMode;
if (m_map_mode == mode)
m_widget->toolButtonNormalMapMode->setChecked(false); { // no change in map mode
m_widget->toolButtonMagicWaypointMapMode->setChecked(true); switch (mode)
{ // make sure the UI buttons are set correctly
showMagicWaypointControls(); case Normal_MapMode:
m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
// delete the normal waypoints from the map m_widget->toolButtonNormalMapMode->setChecked(true);
m_waypoint_list_mutex.lock(); break;
foreach (t_waypoint *wp, m_waypoint_list) case MagicWaypoint_MapMode:
{ m_widget->toolButtonNormalMapMode->setChecked(false);
if (!wp) continue; m_widget->toolButtonMagicWaypointMapMode->setChecked(true);
if (!wp->map_wp_item) continue; break;
wp->coord = wp->map_wp_item->Coord(); }
wp->altitude = wp->map_wp_item->Altitude(); return;
wp->description = wp->map_wp_item->Description(); }
wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0;
wp->map_wp_item = NULL; switch (mode)
} {
m_map->WPDeleteAll(); case Normal_MapMode:
m_waypoint_list_mutex.unlock(); m_map_mode = Normal_MapMode;
// restore the magic waypoint on the map m_widget->toolButtonMagicWaypointMapMode->setChecked(false);
magic_waypoint.map_wp_item = m_map->WPCreate(magic_waypoint.coord, magic_waypoint.altitude, magic_waypoint.description); m_widget->toolButtonNormalMapMode->setChecked(true);
magic_waypoint.map_wp_item->setZValue(10 + magic_waypoint.map_wp_item->Number());
magic_waypoint.map_wp_item->SetShowNumber(false); hideMagicWaypointControls();
magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png"));
// delete the magic waypoint from the map
break; if (m_magic_waypoint.map_wp_item)
} {
} m_magic_waypoint.coord = m_magic_waypoint.map_wp_item->Coord();
m_magic_waypoint.altitude = m_magic_waypoint.map_wp_item->Altitude();
// ************************************************************************************* m_magic_waypoint.description = m_magic_waypoint.map_wp_item->Description();
// Context menu stuff m_magic_waypoint.map_wp_item = NULL;
}
void OPMapGadgetWidget::createActions() m_map->WPDeleteAll();
{
if (!m_widget) // restore the normal waypoints on the map
return; m_waypoint_list_mutex.lock();
foreach (t_waypoint *wp, m_waypoint_list)
// *********************** {
// create menu actions if (!wp) continue;
wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description);
closeAct1 = new QAction(tr("Close menu"), this); if (!wp->map_wp_item) continue;
closeAct1->setStatusTip(tr("Close the context menu")); wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number());
wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked);
closeAct2 = new QAction(tr("Close menu"), this); if (!wp->locked)
closeAct2->setStatusTip(tr("Close the context menu")); wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png"));
else
reloadAct = new QAction(tr("&Reload map"), this); wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png"));
reloadAct->setShortcut(tr("F5")); wp->map_wp_item->update();
reloadAct->setStatusTip(tr("Reload the map tiles")); }
connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); m_waypoint_list_mutex.unlock();
copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this); break;
copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard"));
connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered())); case MagicWaypoint_MapMode:
m_map_mode = MagicWaypoint_MapMode;
copyMouseLatToClipAct = new QAction(tr("Mouse latitude"), this);
copyMouseLatToClipAct->setStatusTip(tr("Copy the mouse latitude to the clipboard")); m_widget->toolButtonNormalMapMode->setChecked(false);
connect(copyMouseLatToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatToClipAct_triggered())); m_widget->toolButtonMagicWaypointMapMode->setChecked(true);
copyMouseLonToClipAct = new QAction(tr("Mouse longitude"), this); showMagicWaypointControls();
copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard"));
connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered())); // delete the normal waypoints from the map
m_waypoint_list_mutex.lock();
/* foreach (t_waypoint *wp, m_waypoint_list)
findPlaceAct = new QAction(tr("&Find place"), this); {
findPlaceAct->setShortcut(tr("Ctrl+F")); if (!wp) continue;
findPlaceAct->setStatusTip(tr("Find a location")); if (!wp->map_wp_item) continue;
connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered())); wp->coord = wp->map_wp_item->Coord();
*/ wp->altitude = wp->map_wp_item->Altitude();
wp->description = wp->map_wp_item->Description();
showCompassAct = new QAction(tr("Show compass"), this); wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0;
showCompassAct->setStatusTip(tr("Show/Hide the compass")); wp->map_wp_item = NULL;
showCompassAct->setCheckable(true); }
showCompassAct->setChecked(true); m_map->WPDeleteAll();
connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(onShowCompassAct_toggled(bool))); m_waypoint_list_mutex.unlock();
showDiagnostics = new QAction(tr("Show Diagnostics"), this); // restore the magic waypoint on the map
showDiagnostics->setStatusTip(tr("Show/Hide the diagnostics")); m_magic_waypoint.map_wp_item = m_map->WPCreate(m_magic_waypoint.coord, m_magic_waypoint.altitude, m_magic_waypoint.description);
showDiagnostics->setCheckable(true); m_magic_waypoint.map_wp_item->setZValue(10 + m_magic_waypoint.map_wp_item->Number());
showDiagnostics->setChecked(false); m_magic_waypoint.map_wp_item->SetShowNumber(false);
connect(showDiagnostics, SIGNAL(toggled(bool)), this, SLOT(onShowDiagnostics_toggled(bool))); m_magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png"));
showHomeAct = new QAction(tr("Show Home"), this); break;
showHomeAct->setStatusTip(tr("Show/Hide the Home location")); }
showHomeAct->setCheckable(true); }
showHomeAct->setChecked(true);
connect(showHomeAct, SIGNAL(toggled(bool)), this, SLOT(onShowHomeAct_toggled(bool))); // *************************************************************************************
// Context menu stuff
showUAVAct = new QAction(tr("Show UAV"), this);
showUAVAct->setStatusTip(tr("Show/Hide the UAV")); void OPMapGadgetWidget::createActions()
showUAVAct->setCheckable(true); {
showUAVAct->setChecked(true); int list_size;
connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool)));
if (!m_widget || !m_map)
zoomInAct = new QAction(tr("Zoom &In"), this); return;
zoomInAct->setShortcut(Qt::Key_PageUp);
zoomInAct->setStatusTip(tr("Zoom the map in")); // ***********************
connect(zoomInAct, SIGNAL(triggered()), this, SLOT(onGoZoomInAct_triggered())); // create menu actions
zoomOutAct = new QAction(tr("Zoom &Out"), this); closeAct1 = new QAction(tr("Close menu"), this);
zoomOutAct->setShortcut(Qt::Key_PageDown); closeAct1->setStatusTip(tr("Close the context menu"));
zoomOutAct->setStatusTip(tr("Zoom the map out"));
connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(onGoZoomOutAct_triggered())); closeAct2 = new QAction(tr("Close menu"), this);
closeAct2->setStatusTip(tr("Close the context menu"));
goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this);
goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse")); reloadAct = new QAction(tr("&Reload map"), this);
connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(onGoMouseClickAct_triggered())); reloadAct->setShortcut(tr("F5"));
reloadAct->setStatusTip(tr("Reload the map tiles"));
setHomeAct = new QAction(tr("Set the home location"), this); connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered()));
setHomeAct->setStatusTip(tr("Set the home location to where you clicked"));
#if !defined(allow_manual_home_location_move) copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this);
setHomeAct->setEnabled(false); copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard"));
#endif connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered()));
connect(setHomeAct, SIGNAL(triggered()), this, SLOT(onSetHomeAct_triggered()));
copyMouseLatToClipAct = new QAction(tr("Mouse latitude"), this);
goHomeAct = new QAction(tr("Go to &Home location"), this); copyMouseLatToClipAct->setStatusTip(tr("Copy the mouse latitude to the clipboard"));
goHomeAct->setShortcut(tr("Ctrl+H")); connect(copyMouseLatToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatToClipAct_triggered()));
goHomeAct->setStatusTip(tr("Center the map onto the home location"));
connect(goHomeAct, SIGNAL(triggered()), this, SLOT(onGoHomeAct_triggered())); copyMouseLonToClipAct = new QAction(tr("Mouse longitude"), this);
copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard"));
goUAVAct = new QAction(tr("Go to &UAV location"), this); connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered()));
goUAVAct->setShortcut(tr("Ctrl+U"));
goUAVAct->setStatusTip(tr("Center the map onto the UAV location")); /*
connect(goUAVAct, SIGNAL(triggered()), this, SLOT(onGoUAVAct_triggered())); findPlaceAct = new QAction(tr("&Find place"), this);
findPlaceAct->setShortcut(tr("Ctrl+F"));
followUAVpositionAct = new QAction(tr("Follow UAV position"), this); findPlaceAct->setStatusTip(tr("Find a location"));
followUAVpositionAct->setShortcut(tr("Ctrl+F")); connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered()));
followUAVpositionAct->setStatusTip(tr("Keep the map centered onto the UAV")); */
followUAVpositionAct->setCheckable(true);
followUAVpositionAct->setChecked(false); showCompassAct = new QAction(tr("Show compass"), this);
connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVpositionAct_toggled(bool))); showCompassAct->setStatusTip(tr("Show/Hide the compass"));
showCompassAct->setCheckable(true);
followUAVheadingAct = new QAction(tr("Follow UAV heading"), this); showCompassAct->setChecked(true);
followUAVheadingAct->setShortcut(tr("Ctrl+F")); connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(onShowCompassAct_toggled(bool)));
followUAVheadingAct->setStatusTip(tr("Keep the map rotation to the UAV heading"));
followUAVheadingAct->setCheckable(true); showDiagnostics = new QAction(tr("Show Diagnostics"), this);
followUAVheadingAct->setChecked(false); showDiagnostics->setStatusTip(tr("Show/Hide the diagnostics"));
connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); showDiagnostics->setCheckable(true);
showDiagnostics->setChecked(false);
/* connect(showDiagnostics, SIGNAL(toggled(bool)), this, SLOT(onShowDiagnostics_toggled(bool)));
TODO: Waypoint support is disabled for v1.0
*/ showHomeAct = new QAction(tr("Show Home"), this);
showHomeAct->setStatusTip(tr("Show/Hide the Home location"));
/* showHomeAct->setCheckable(true);
wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); showHomeAct->setChecked(true);
wayPointEditorAct->setShortcut(tr("Ctrl+W")); connect(showHomeAct, SIGNAL(toggled(bool)), this, SLOT(onShowHomeAct_toggled(bool)));
wayPointEditorAct->setStatusTip(tr("Open the waypoint editor"));
wayPointEditorAct->setEnabled(false); // temporary showUAVAct = new QAction(tr("Show UAV"), this);
connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); showUAVAct->setStatusTip(tr("Show/Hide the UAV"));
showUAVAct->setCheckable(true);
addWayPointAct = new QAction(tr("&Add waypoint"), this); showUAVAct->setChecked(true);
addWayPointAct->setShortcut(tr("Ctrl+A")); connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool)));
addWayPointAct->setStatusTip(tr("Add waypoint"));
connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); zoomInAct = new QAction(tr("Zoom &In"), this);
zoomInAct->setShortcut(Qt::Key_PageUp);
editWayPointAct = new QAction(tr("&Edit waypoint"), this); zoomInAct->setStatusTip(tr("Zoom the map in"));
editWayPointAct->setShortcut(tr("Ctrl+E")); connect(zoomInAct, SIGNAL(triggered()), this, SLOT(onGoZoomInAct_triggered()));
editWayPointAct->setStatusTip(tr("Edit waypoint"));
connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(onEditWayPointAct_triggered())); zoomOutAct = new QAction(tr("Zoom &Out"), this);
zoomOutAct->setShortcut(Qt::Key_PageDown);
lockWayPointAct = new QAction(tr("&Lock waypoint"), this); zoomOutAct->setStatusTip(tr("Zoom the map out"));
lockWayPointAct->setStatusTip(tr("Lock/Unlock a waypoint")); connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(onGoZoomOutAct_triggered()));
lockWayPointAct->setCheckable(true);
lockWayPointAct->setChecked(false); goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this);
connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered())); goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse"));
connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(onGoMouseClickAct_triggered()));
deleteWayPointAct = new QAction(tr("&Delete waypoint"), this);
deleteWayPointAct->setShortcut(tr("Ctrl+D")); setHomeAct = new QAction(tr("Set the home location"), this);
deleteWayPointAct->setStatusTip(tr("Delete waypoint")); setHomeAct->setStatusTip(tr("Set the home location to where you clicked"));
connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered())); #if !defined(allow_manual_home_location_move)
setHomeAct->setEnabled(false);
clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); #endif
clearWayPointsAct->setShortcut(tr("Ctrl+C")); connect(setHomeAct, SIGNAL(triggered()), this, SLOT(onSetHomeAct_triggered()));
clearWayPointsAct->setStatusTip(tr("Clear waypoints"));
connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); goHomeAct = new QAction(tr("Go to &Home location"), this);
*/ goHomeAct->setShortcut(tr("Ctrl+H"));
goHomeAct->setStatusTip(tr("Center the map onto the home location"));
homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); connect(goHomeAct, SIGNAL(triggered()), this, SLOT(onGoHomeAct_triggered()));
homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position"));
connect(homeMagicWaypointAct, SIGNAL(triggered()), this, SLOT(onHomeMagicWaypointAct_triggered())); goUAVAct = new QAction(tr("Go to &UAV location"), this);
goUAVAct->setShortcut(tr("Ctrl+U"));
mapModeActGroup = new QActionGroup(this); goUAVAct->setStatusTip(tr("Center the map onto the UAV location"));
connect(mapModeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMapModeActGroup_triggered(QAction *))); connect(goUAVAct, SIGNAL(triggered()), this, SLOT(onGoUAVAct_triggered()));
mapModeAct.clear();
{ followUAVpositionAct = new QAction(tr("Follow UAV position"), this);
QAction *map_mode_act; followUAVpositionAct->setShortcut(tr("Ctrl+F"));
followUAVpositionAct->setStatusTip(tr("Keep the map centered onto the UAV"));
map_mode_act = new QAction(tr("Normal"), mapModeActGroup); followUAVpositionAct->setCheckable(true);
map_mode_act->setCheckable(true); followUAVpositionAct->setChecked(false);
map_mode_act->setChecked(m_map_mode == Normal_MapMode); connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVpositionAct_toggled(bool)));
map_mode_act->setData((int)Normal_MapMode);
mapModeAct.append(map_mode_act); followUAVheadingAct = new QAction(tr("Follow UAV heading"), this);
followUAVheadingAct->setShortcut(tr("Ctrl+F"));
map_mode_act = new QAction(tr("Magic Waypoint"), mapModeActGroup); followUAVheadingAct->setStatusTip(tr("Keep the map rotation to the UAV heading"));
map_mode_act->setCheckable(true); followUAVheadingAct->setCheckable(true);
map_mode_act->setChecked(m_map_mode == MagicWaypoint_MapMode); followUAVheadingAct->setChecked(false);
map_mode_act->setData((int)MagicWaypoint_MapMode); connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool)));
mapModeAct.append(map_mode_act);
} /*
TODO: Waypoint support is disabled for v1.0
zoomActGroup = new QActionGroup(this); */
connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onZoomActGroup_triggered(QAction *)));
zoomAct.clear(); /*
for (int i = min_zoom; i <= max_zoom; i++) wayPointEditorAct = new QAction(tr("&Waypoint editor"), this);
{ wayPointEditorAct->setShortcut(tr("Ctrl+W"));
QAction *zoom_act = new QAction(QString::number(i), zoomActGroup); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor"));
zoom_act->setCheckable(true); wayPointEditorAct->setEnabled(false); // temporary
zoom_act->setData(i); connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered()));
zoomAct.append(zoom_act);
} addWayPointAct = new QAction(tr("&Add waypoint"), this);
addWayPointAct->setShortcut(tr("Ctrl+A"));
// ***** addWayPointAct->setStatusTip(tr("Add waypoint"));
// safe area connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered()));
showSafeAreaAct = new QAction(tr("Show Safe Area"), this); editWayPointAct = new QAction(tr("&Edit waypoint"), this);
showSafeAreaAct->setStatusTip(tr("Show/Hide the Safe Area around the home location")); editWayPointAct->setShortcut(tr("Ctrl+E"));
showSafeAreaAct->setCheckable(true); editWayPointAct->setStatusTip(tr("Edit waypoint"));
showSafeAreaAct->setChecked(m_map->Home->ShowSafeArea()); connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(onEditWayPointAct_triggered()));
connect(showSafeAreaAct, SIGNAL(toggled(bool)), this, SLOT(onShowSafeAreaAct_toggled(bool)));
lockWayPointAct = new QAction(tr("&Lock waypoint"), this);
safeAreaActGroup = new QActionGroup(this); lockWayPointAct->setStatusTip(tr("Lock/Unlock a waypoint"));
connect(safeAreaActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onSafeAreaActGroup_triggered(QAction *))); lockWayPointAct->setCheckable(true);
safeAreaAct.clear(); lockWayPointAct->setChecked(false);
for (int i = 0; i < (int)(sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0])); i++) connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered()));
{
int safeArea = safe_area_radius_list[i]; deleteWayPointAct = new QAction(tr("&Delete waypoint"), this);
QAction *safeArea_act = new QAction(QString::number(safeArea) + "m", safeAreaActGroup); deleteWayPointAct->setShortcut(tr("Ctrl+D"));
safeArea_act->setCheckable(true); deleteWayPointAct->setStatusTip(tr("Delete waypoint"));
safeArea_act->setChecked(safeArea == m_map->Home->SafeArea()); connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered()));
safeArea_act->setData(safeArea);
safeAreaAct.append(safeArea_act); clearWayPointsAct = new QAction(tr("&Clear waypoints"), this);
} clearWayPointsAct->setShortcut(tr("Ctrl+C"));
clearWayPointsAct->setStatusTip(tr("Clear waypoints"));
// ***** connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered()));
// UAV trail */
uavTrailTypeActGroup = new QActionGroup(this); homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this);
connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *))); homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position"));
uavTrailTypeAct.clear(); connect(homeMagicWaypointAct, SIGNAL(triggered()), this, SLOT(onHomeMagicWaypointAct_triggered()));
QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes();
for (int i = 0; i < uav_trail_type_list.count(); i++) mapModeActGroup = new QActionGroup(this);
{ connect(mapModeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMapModeActGroup_triggered(QAction *)));
mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[i]); mapModeAct.clear();
QAction *uavTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(uav_trail_type), uavTrailTypeActGroup); {
uavTrailType_act->setCheckable(true); QAction *map_mode_act;
uavTrailType_act->setChecked(uav_trail_type == m_map->UAV->GetTrailType());
uavTrailType_act->setData(i); map_mode_act = new QAction(tr("Normal"), mapModeActGroup);
uavTrailTypeAct.append(uavTrailType_act); map_mode_act->setCheckable(true);
} map_mode_act->setChecked(m_map_mode == Normal_MapMode);
map_mode_act->setData((int)Normal_MapMode);
showTrailAct = new QAction(tr("Show Trail dots"), this); mapModeAct.append(map_mode_act);
showTrailAct->setStatusTip(tr("Show/Hide the Trail dots"));
showTrailAct->setCheckable(true); map_mode_act = new QAction(tr("Magic Waypoint"), mapModeActGroup);
showTrailAct->setChecked(true); map_mode_act->setCheckable(true);
connect(showTrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailAct_toggled(bool))); map_mode_act->setChecked(m_map_mode == MagicWaypoint_MapMode);
map_mode_act->setData((int)MagicWaypoint_MapMode);
showTrailLineAct = new QAction(tr("Show Trail lines"), this); mapModeAct.append(map_mode_act);
showTrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); }
showTrailLineAct->setCheckable(true);
showTrailLineAct->setChecked(true); zoomActGroup = new QActionGroup(this);
connect(showTrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailLineAct_toggled(bool))); connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onZoomActGroup_triggered(QAction *)));
zoomAct.clear();
clearUAVtrailAct = new QAction(tr("Clear UAV trail"), this); for (int i = m_min_zoom; i <= m_max_zoom; i++)
clearUAVtrailAct->setStatusTip(tr("Clear the UAV trail")); {
connect(clearUAVtrailAct, SIGNAL(triggered()), this, SLOT(onClearUAVtrailAct_triggered())); QAction *zoom_act = new QAction(QString::number(i), zoomActGroup);
zoom_act->setCheckable(true);
uavTrailTimeActGroup = new QActionGroup(this); zoom_act->setData(i);
connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *))); zoomAct.append(zoom_act);
uavTrailTimeAct.clear(); }
for (int i = 0; i < (int)(sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0])); i++)
{ maxUpdateRateActGroup = new QActionGroup(this);
int uav_trail_time = uav_trail_time_list[i]; connect(maxUpdateRateActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMaxUpdateRateActGroup_triggered(QAction *)));
QAction *uavTrailTime_act = new QAction(QString::number(uav_trail_time) + " sec", uavTrailTimeActGroup); maxUpdateRateAct.clear();
uavTrailTime_act->setCheckable(true); list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]);
uavTrailTime_act->setChecked(uav_trail_time == m_map->UAV->TrailTime()); for (int i = 0; i < list_size; i++)
uavTrailTime_act->setData(uav_trail_time); {
uavTrailTimeAct.append(uavTrailTime_act); QAction *maxUpdateRate_act;
} int j = max_update_rate_list[i];
maxUpdateRate_act = new QAction(QString::number(j), maxUpdateRateActGroup);
uavTrailDistanceActGroup = new QActionGroup(this); maxUpdateRate_act->setCheckable(true);
connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *))); maxUpdateRate_act->setData(j);
uavTrailDistanceAct.clear(); maxUpdateRate_act->setChecked(j == m_maxUpdateRate);
for (int i = 0; i < (int)(sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0])); i++) maxUpdateRateAct.append(maxUpdateRate_act);
{ }
int uav_trail_distance = uav_trail_distance_list[i];
QAction *uavTrailDistance_act = new QAction(QString::number(uav_trail_distance) + " meters", uavTrailDistanceActGroup); // *****
uavTrailDistance_act->setCheckable(true); // safe area
uavTrailDistance_act->setChecked(uav_trail_distance == m_map->UAV->TrailDistance());
uavTrailDistance_act->setData(uav_trail_distance); showSafeAreaAct = new QAction(tr("Show Safe Area"), this);
uavTrailDistanceAct.append(uavTrailDistance_act); showSafeAreaAct->setStatusTip(tr("Show/Hide the Safe Area around the home location"));
} showSafeAreaAct->setCheckable(true);
showSafeAreaAct->setChecked(m_map->Home->ShowSafeArea());
// ***** connect(showSafeAreaAct, SIGNAL(toggled(bool)), this, SLOT(onShowSafeAreaAct_toggled(bool)));
// *********************** safeAreaActGroup = new QActionGroup(this);
} connect(safeAreaActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onSafeAreaActGroup_triggered(QAction *)));
safeAreaAct.clear();
void OPMapGadgetWidget::onReloadAct_triggered() list_size = sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0]);
{ for (int i = 0; i < list_size; i++)
if (!m_widget || !m_map) {
return; int safeArea = safe_area_radius_list[i];
QAction *safeArea_act = new QAction(QString::number(safeArea) + "m", safeAreaActGroup);
m_map->ReloadMap(); safeArea_act->setCheckable(true);
} safeArea_act->setChecked(safeArea == m_map->Home->SafeArea());
safeArea_act->setData(safeArea);
void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() safeAreaAct.append(safeArea_act);
{ }
// QClipboard *clipboard = qApp->clipboard();
QClipboard *clipboard = QApplication::clipboard(); // *****
clipboard->setText(QString::number(context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); // UAV trail
}
uavTrailTypeActGroup = new QActionGroup(this);
void OPMapGadgetWidget::onCopyMouseLatToClipAct_triggered() connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *)));
{ uavTrailTypeAct.clear();
// QClipboard *clipboard = qApp->clipboard(); QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes();
QClipboard *clipboard = QApplication::clipboard(); for (int i = 0; i < uav_trail_type_list.count(); i++)
clipboard->setText(QString::number(context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard); {
} mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[i]);
QAction *uavTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(uav_trail_type), uavTrailTypeActGroup);
void OPMapGadgetWidget::onCopyMouseLonToClipAct_triggered() uavTrailType_act->setCheckable(true);
{ uavTrailType_act->setChecked(uav_trail_type == m_map->UAV->GetTrailType());
// QClipboard *clipboard = qApp->clipboard(); uavTrailType_act->setData(i);
QClipboard *clipboard = QApplication::clipboard(); uavTrailTypeAct.append(uavTrailType_act);
clipboard->setText(QString::number(context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); }
}
showTrailAct = new QAction(tr("Show Trail dots"), this);
showTrailAct->setStatusTip(tr("Show/Hide the Trail dots"));
void OPMapGadgetWidget::onShowCompassAct_toggled(bool show) showTrailAct->setCheckable(true);
{ showTrailAct->setChecked(true);
if (!m_widget || !m_map) connect(showTrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailAct_toggled(bool)));
return;
showTrailLineAct = new QAction(tr("Show Trail lines"), this);
m_map->SetShowCompass(show); showTrailLineAct->setStatusTip(tr("Show/Hide the Trail lines"));
} showTrailLineAct->setCheckable(true);
showTrailLineAct->setChecked(true);
void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show) connect(showTrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailLineAct_toggled(bool)));
{
if (!m_widget || !m_map) clearUAVtrailAct = new QAction(tr("Clear UAV trail"), this);
return; clearUAVtrailAct->setStatusTip(tr("Clear the UAV trail"));
connect(clearUAVtrailAct, SIGNAL(triggered()), this, SLOT(onClearUAVtrailAct_triggered()));
m_map->SetShowDiagnostics(show);
} uavTrailTimeActGroup = new QActionGroup(this);
connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *)));
void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) uavTrailTimeAct.clear();
{ list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]);
if (!m_widget || !m_map) for (int i = 0; i < list_size; i++)
return; {
int uav_trail_time = uav_trail_time_list[i];
m_map->Home->setVisible(show); QAction *uavTrailTime_act = new QAction(QString::number(uav_trail_time) + " sec", uavTrailTimeActGroup);
} uavTrailTime_act->setCheckable(true);
uavTrailTime_act->setChecked(uav_trail_time == m_map->UAV->TrailTime());
void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) uavTrailTime_act->setData(uav_trail_time);
{ uavTrailTimeAct.append(uavTrailTime_act);
if (!m_widget || !m_map) }
return;
uavTrailDistanceActGroup = new QActionGroup(this);
m_map->UAV->setVisible(show); connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *)));
m_map->GPS->setVisible(show); uavTrailDistanceAct.clear();
} list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]);
for (int i = 0; i < list_size; i++)
void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) {
{ int uav_trail_distance = uav_trail_distance_list[i];
if (!m_widget || !m_map) QAction *uavTrailDistance_act = new QAction(QString::number(uav_trail_distance) + " meters", uavTrailDistanceActGroup);
return; uavTrailDistance_act->setCheckable(true);
uavTrailDistance_act->setChecked(uav_trail_distance == m_map->UAV->TrailDistance());
m_map->UAV->SetShowTrail(show); uavTrailDistance_act->setData(uav_trail_distance);
m_map->GPS->SetShowTrail(show); uavTrailDistanceAct.append(uavTrailDistance_act);
} }
void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) // *****
{
if (!m_widget || !m_map) // ***********************
return; }
m_map->UAV->SetShowTrailLine(show); void OPMapGadgetWidget::onReloadAct_triggered()
m_map->GPS->SetShowTrailLine(show); {
} if (!m_widget || !m_map)
return;
void OPMapGadgetWidget::onMapModeActGroup_triggered(QAction *action)
{ m_map->ReloadMap();
if (!m_widget || !m_map || !action) }
return;
void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered()
opMapModeType mode = (opMapModeType)action->data().toInt(); {
QClipboard *clipboard = QApplication::clipboard();
setMapMode(mode); clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard);
} }
void OPMapGadgetWidget::onGoZoomInAct_triggered() void OPMapGadgetWidget::onCopyMouseLatToClipAct_triggered()
{ {
zoomIn(); QClipboard *clipboard = QApplication::clipboard();
} clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard);
}
void OPMapGadgetWidget::onGoZoomOutAct_triggered()
{ void OPMapGadgetWidget::onCopyMouseLonToClipAct_triggered()
zoomOut(); {
} QClipboard *clipboard = QApplication::clipboard();
clipboard->setText(QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard);
void OPMapGadgetWidget::onZoomActGroup_triggered(QAction *action) }
{
if (!m_widget || !action)
return; void OPMapGadgetWidget::onShowCompassAct_toggled(bool show)
{
setZoom(action->data().toInt()); if (!m_widget || !m_map)
} return;
void OPMapGadgetWidget::onGoMouseClickAct_triggered() m_map->SetShowCompass(show);
{ }
if (!m_widget || !m_map)
return; void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show)
{
m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position if (!m_widget || !m_map)
} return;
void OPMapGadgetWidget::onSetHomeAct_triggered() m_map->SetShowDiagnostics(show);
{ }
if (!m_widget || !m_map)
return; void OPMapGadgetWidget::onShowHomeAct_toggled(bool show)
{
setHome(context_menu_lat_lon); if (!m_widget || !m_map)
return;
setHomeLocationObject(); // update the HomeLocation UAVObject
} m_map->Home->setVisible(show);
}
void OPMapGadgetWidget::onGoHomeAct_triggered()
{ void OPMapGadgetWidget::onShowUAVAct_toggled(bool show)
if (!m_widget || !m_map) {
return; if (!m_widget || !m_map)
return;
goHome();
} m_map->UAV->setVisible(show);
m_map->GPS->setVisible(show);
void OPMapGadgetWidget::onGoUAVAct_triggered() }
{
if (!m_widget || !m_map) void OPMapGadgetWidget::onShowTrailAct_toggled(bool show)
return; {
if (!m_widget || !m_map)
double latitude; return;
double longitude;
double altitude; m_map->UAV->SetShowTrail(show);
if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position m_map->GPS->SetShowTrail(show);
{ }
internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position
internals::PointLatLng map_pos = m_map->CurrentPosition(); // current MAP position void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show)
if (map_pos != uav_pos) m_map->SetCurrentPosition(uav_pos); // center the map onto the UAV {
} if (!m_widget || !m_map)
} return;
void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked) m_map->UAV->SetShowTrailLine(show);
{ m_map->GPS->SetShowTrailLine(show);
if (!m_widget || !m_map) }
return;
void OPMapGadgetWidget::onMapModeActGroup_triggered(QAction *action)
if (m_widget->toolButtonMapUAV->isChecked() != checked) {
m_widget->toolButtonMapUAV->setChecked(checked); if (!m_widget || !m_map || !action)
return;
setMapFollowingMode();
} opMapModeType mode = (opMapModeType)action->data().toInt();
void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) setMapMode(mode);
{ }
if (!m_widget || !m_map)
return; void OPMapGadgetWidget::onGoZoomInAct_triggered()
{
if (m_widget->toolButtonMapUAVheading->isChecked() != checked) zoomIn();
m_widget->toolButtonMapUAVheading->setChecked(checked); }
setMapFollowingMode(); void OPMapGadgetWidget::onGoZoomOutAct_triggered()
} {
zoomOut();
void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) }
{
if (!m_widget || !m_map) void OPMapGadgetWidget::onZoomActGroup_triggered(QAction *action)
return; {
if (!m_widget || !m_map || !action)
int trail_type_idx = action->data().toInt(); return;
QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); setZoom(action->data().toInt());
mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[trail_type_idx]); }
m_map->UAV->SetTrailType(uav_trail_type); void OPMapGadgetWidget::onMaxUpdateRateActGroup_triggered(QAction *action)
} {
if (!m_widget || !m_map || !action)
void OPMapGadgetWidget::onClearUAVtrailAct_triggered() return;
{
if (!m_widget || !m_map) setMaxUpdateRate(action->data().toInt());
return; }
m_map->UAV->DeleteTrail(); void OPMapGadgetWidget::onGoMouseClickAct_triggered()
m_map->GPS->DeleteTrail(); {
} if (!m_widget || !m_map)
return;
void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action)
{ m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position
if (!m_widget || !m_map) }
return;
void OPMapGadgetWidget::onSetHomeAct_triggered()
int trail_time = (double)action->data().toInt(); {
if (!m_widget || !m_map)
m_map->UAV->SetTrailTime(trail_time); return;
}
setHome(m_context_menu_lat_lon);
void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action)
{ setHomeLocationObject(); // update the HomeLocation UAVObject
if (!m_widget || !m_map) }
return;
void OPMapGadgetWidget::onGoHomeAct_triggered()
int trail_distance = action->data().toInt(); {
if (!m_widget || !m_map)
m_map->UAV->SetTrailDistance(trail_distance); return;
}
goHome();
/** }
* TODO: unused for v1.0
**/ void OPMapGadgetWidget::onGoUAVAct_triggered()
/* {
void OPMapGadgetWidget::onAddWayPointAct_triggered() if (!m_widget || !m_map)
{ return;
if (!m_widget || !m_map)
return; double latitude;
double longitude;
if (m_map_mode != Normal_MapMode) double altitude;
return; if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position
{
m_waypoint_list_mutex.lock(); internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position
internals::PointLatLng map_pos = m_map->CurrentPosition(); // current MAP position
// create a waypoint on the map at the last known mouse position if (map_pos != uav_pos) m_map->SetCurrentPosition(uav_pos); // center the map onto the UAV
t_waypoint *wp = new t_waypoint; }
wp->map_wp_item = NULL; }
wp->coord = context_menu_lat_lon;
wp->altitude = 0; void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked)
wp->description = ""; {
wp->locked = false; if (!m_widget || !m_map)
wp->time_seconds = 0; return;
wp->hold_time_seconds = 0;
wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); if (m_widget->toolButtonMapUAV->isChecked() != checked)
m_widget->toolButtonMapUAV->setChecked(checked);
wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number());
setMapFollowingMode();
wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); }
if (wp->map_wp_item) void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked)
{ {
if (!wp->locked) if (!m_widget || !m_map)
wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); return;
else
wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); if (m_widget->toolButtonMapUAVheading->isChecked() != checked)
wp->map_wp_item->update(); m_widget->toolButtonMapUAVheading->setChecked(checked);
}
setMapFollowingMode();
// and remember it in our own local waypoint list }
m_waypoint_list.append(wp);
void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action)
m_waypoint_list_mutex.unlock(); {
} if (!m_widget || !m_map || !action)
*/ return;
/** int trail_type_idx = action->data().toInt();
* Called when the user asks to edit a waypoint from the map
* QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes();
* TODO: should open an interface to edit waypoint properties, or mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[trail_type_idx]);
* propagate the signal to a specific WP plugin (tbd).
**/ m_map->UAV->SetTrailType(uav_trail_type);
/* }
void OPMapGadgetWidget::onEditWayPointAct_triggered()
{ void OPMapGadgetWidget::onClearUAVtrailAct_triggered()
if (!m_widget || !m_map) {
return; if (!m_widget || !m_map)
return;
if (m_map_mode != Normal_MapMode)
return; m_map->UAV->DeleteTrail();
m_map->GPS->DeleteTrail();
if (!m_mouse_waypoint) }
return;
void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action)
//waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); {
if (!m_widget || !m_map || !action)
m_mouse_waypoint = NULL; return;
}
*/ int trail_time = (double)action->data().toInt();
/** m_map->UAV->SetTrailTime(trail_time);
* TODO: unused for v1.0 }
*/
/* void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action)
void OPMapGadgetWidget::onLockWayPointAct_triggered() {
{ if (!m_widget || !m_map || !action)
if (!m_widget || !m_map || !m_mouse_waypoint) return;
return;
int trail_distance = action->data().toInt();
if (m_map_mode != Normal_MapMode)
return; m_map->UAV->SetTrailDistance(trail_distance);
}
bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0;
m_mouse_waypoint->setFlag(QGraphicsItem::ItemIsMovable, locked); /**
* TODO: unused for v1.0
if (!locked) **/
m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); /*
else void OPMapGadgetWidget::onAddWayPointAct_triggered()
m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); {
m_mouse_waypoint->update(); if (!m_widget || !m_map)
return;
m_mouse_waypoint = NULL;
} if (m_map_mode != Normal_MapMode)
*/ return;
/** m_waypoint_list_mutex.lock();
* TODO: unused for v1.0
*/ // create a waypoint on the map at the last known mouse position
/* t_waypoint *wp = new t_waypoint;
void OPMapGadgetWidget::onDeleteWayPointAct_triggered() wp->map_wp_item = NULL;
{ wp->coord = context_menu_lat_lon;
if (!m_widget || !m_map) wp->altitude = 0;
return; wp->description = "";
wp->locked = false;
if (m_map_mode != Normal_MapMode) wp->time_seconds = 0;
return; wp->hold_time_seconds = 0;
wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description);
if (!m_mouse_waypoint)
return; wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number());
bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked);
if (locked) return; // waypoint is locked if (wp->map_wp_item)
{
QMutexLocker locker(&m_waypoint_list_mutex); if (!wp->locked)
wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png"));
for (int i = 0; i < m_waypoint_list.count(); i++) else
{ wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png"));
t_waypoint *wp = m_waypoint_list.at(i); wp->map_wp_item->update();
if (!wp) continue; }
if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue;
// and remember it in our own local waypoint list
// delete the waypoint from the map m_waypoint_list.append(wp);
m_map->WPDelete(wp->map_wp_item);
m_waypoint_list_mutex.unlock();
// delete the waypoint from our local waypoint list }
m_waypoint_list.removeAt(i); */
delete wp; /**
* Called when the user asks to edit a waypoint from the map
break; *
} * TODO: should open an interface to edit waypoint properties, or
// * propagate the signal to a specific WP plugin (tbd).
// foreach (t_waypoint *wp, m_waypoint_list) **/
// { /*
// if (!wp) continue; void OPMapGadgetWidget::onEditWayPointAct_triggered()
// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; {
// if (!m_widget || !m_map)
// // delete the waypoint from the map return;
// m_map->WPDelete(wp->map_wp_item);
// if (m_map_mode != Normal_MapMode)
// // delete the waypoint from our local waypoint list return;
// m_waypoint_list.removeOne(wp);
// if (!m_mouse_waypoint)
// delete wp; return;
//
// break; //waypoint_edit_dialog.editWaypoint(m_mouse_waypoint);
// }
m_mouse_waypoint = NULL;
m_mouse_waypoint = NULL; }
} */
*/
/**
/** * TODO: unused for v1.0
* TODO: No Waypoint support in v1.0 */
*/ /*
/* void OPMapGadgetWidget::onLockWayPointAct_triggered()
void OPMapGadgetWidget::onClearWayPointsAct_triggered() {
{ if (!m_widget || !m_map || !m_mouse_waypoint)
if (!m_widget || !m_map) return;
return;
if (m_map_mode != Normal_MapMode)
if (m_map_mode != Normal_MapMode) return;
return;
bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0;
QMutexLocker locker(&m_waypoint_list_mutex); m_mouse_waypoint->setFlag(QGraphicsItem::ItemIsMovable, locked);
m_map->WPDeleteAll(); if (!locked)
m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png"));
foreach (t_waypoint *wp, m_waypoint_list) else
{ m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png"));
if (wp) m_mouse_waypoint->update();
{
delete wp; m_mouse_waypoint = NULL;
wp = NULL; }
} */
}
/**
m_waypoint_list.clear(); * TODO: unused for v1.0
} */
*/ /*
void OPMapGadgetWidget::onDeleteWayPointAct_triggered()
void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() {
{ if (!m_widget || !m_map)
// center the magic waypoint on the home position return;
homeMagicWaypoint();
} if (m_map_mode != Normal_MapMode)
return;
void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show)
{ if (!m_mouse_waypoint)
if (!m_widget || !m_map) return;
return;
bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0;
m_map->Home->SetShowSafeArea(show); // show the safe area
m_map->Home->RefreshPos(); if (locked) return; // waypoint is locked
}
QMutexLocker locker(&m_waypoint_list_mutex);
void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action)
{ for (int i = 0; i < m_waypoint_list.count(); i++)
if (!m_widget || !m_map) {
return; t_waypoint *wp = m_waypoint_list.at(i);
if (!wp) continue;
int radius = action->data().toInt(); if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue;
m_map->Home->SetSafeArea(radius); // set the radius (meters) // delete the waypoint from the map
m_map->Home->RefreshPos(); m_map->WPDelete(wp->map_wp_item);
// move the magic waypoint if need be to keep it within the safe area around the home position // delete the waypoint from our local waypoint list
keepMagicWaypointWithInSafeArea(); m_waypoint_list.removeAt(i);
}
delete wp;
/**
* move the magic waypoint to the home position break;
**/ }
void OPMapGadgetWidget::homeMagicWaypoint() //
{ // foreach (t_waypoint *wp, m_waypoint_list)
if (!m_widget || !m_map) // {
return; // if (!wp) continue;
// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue;
if (m_map_mode != MagicWaypoint_MapMode) //
return; // // delete the waypoint from the map
// m_map->WPDelete(wp->map_wp_item);
magic_waypoint.coord = home_position.coord; //
// // delete the waypoint from our local waypoint list
if (magic_waypoint.map_wp_item) // m_waypoint_list.removeOne(wp);
magic_waypoint.map_wp_item->SetCoord(magic_waypoint.coord); //
} // delete wp;
//
// ************************************************************************************* // break;
// move the UAV to the magic waypoint position // }
void OPMapGadgetWidget::moveToMagicWaypointPosition() m_mouse_waypoint = NULL;
{ }
if (!m_widget || !m_map) */
return;
/**
if (m_map_mode != MagicWaypoint_MapMode) * TODO: No Waypoint support in v1.0
return; */
/*
// internals::PointLatLng coord = magic_waypoint.coord; void OPMapGadgetWidget::onClearWayPointsAct_triggered()
// double altitude = magic_waypoint.altitude; {
if (!m_widget || !m_map)
return;
// ToDo:
if (m_map_mode != Normal_MapMode)
} return;
// ************************************************************************************* QMutexLocker locker(&m_waypoint_list_mutex);
// temporary until an object is created for managing the save/restore
m_map->WPDeleteAll();
// load the contents of a simple text file into a combobox
void OPMapGadgetWidget::loadComboBoxLines(QComboBox *comboBox, QString filename) foreach (t_waypoint *wp, m_waypoint_list)
{ {
if (!comboBox) return; if (wp)
if (filename.isNull() || filename.isEmpty()) return; {
delete wp;
QFile file(filename); wp = NULL;
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) }
return; }
QTextStream in(&file); m_waypoint_list.clear();
}
while (!in.atEnd()) */
{
QString line = in.readLine().simplified(); void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered()
if (line.isNull() || line.isEmpty()) continue; {
comboBox->addItem(line); // center the magic waypoint on the home position
} homeMagicWaypoint();
}
file.close();
} void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show)
{
// save a combobox text contents to a simple text file if (!m_widget || !m_map)
void OPMapGadgetWidget::saveComboBoxLines(QComboBox *comboBox, QString filename) return;
{
if (!comboBox) return; m_map->Home->SetShowSafeArea(show); // show the safe area
if (filename.isNull() || filename.isEmpty()) return; m_map->Home->RefreshPos();
}
QFile file(filename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action)
return; {
if (!m_widget || !m_map || !action)
QTextStream out(&file); return;
for (int i = 0; i < comboBox->count(); i++) int radius = action->data().toInt();
{
QString line = comboBox->itemText(i).simplified(); m_map->Home->SetSafeArea(radius); // set the radius (meters)
if (line.isNull() || line.isEmpty()) continue; m_map->Home->RefreshPos();
out << line << "\n";
} // move the magic waypoint if need be to keep it within the safe area around the home position
keepMagicWaypointWithInSafeArea();
file.close(); }
}
/**
// ************************************************************************************* * move the magic waypoint to the home position
// show/hide the magic waypoint controls **/
void OPMapGadgetWidget::homeMagicWaypoint()
void OPMapGadgetWidget::hideMagicWaypointControls() {
{ if (!m_widget || !m_map)
m_widget->lineWaypoint->setVisible(false); return;
m_widget->toolButtonHomeWaypoint->setVisible(false);
m_widget->toolButtonMoveToWP->setVisible(false); if (m_map_mode != MagicWaypoint_MapMode)
} return;
void OPMapGadgetWidget::showMagicWaypointControls() m_magic_waypoint.coord = m_home_position.coord;
{
m_widget->lineWaypoint->setVisible(true); if (m_magic_waypoint.map_wp_item)
m_widget->toolButtonHomeWaypoint->setVisible(true); m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord);
}
#if defined(allow_manual_home_location_move)
m_widget->toolButtonMoveToWP->setVisible(true); // *************************************************************************************
#else // move the UAV to the magic waypoint position
m_widget->toolButtonMoveToWP->setVisible(false);
#endif void OPMapGadgetWidget::moveToMagicWaypointPosition()
} {
if (!m_widget || !m_map)
// ************************************************************************************* return;
// move the magic waypoint to keep it within the safe area boundry
if (m_map_mode != MagicWaypoint_MapMode)
void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() return;
{
// internals::PointLatLng coord = magic_waypoint.coord;
// calcute the bearing and distance from the home position to the magic waypoint // double altitude = magic_waypoint.altitude;
double dist = distance(home_position.coord, magic_waypoint.coord);
double bear = bearing(home_position.coord, magic_waypoint.coord);
// ToDo:
// get the maximum safe distance - in kilometers
double boundry_dist = (double)m_map->Home->SafeArea() / 1000; }
// if (dist <= boundry_dist) // *************************************************************************************
// return; // the magic waypoint is still within the safe area, don't move it // temporary until an object is created for managing the save/restore
if (dist > boundry_dist) dist = boundry_dist; // load the contents of a simple text file into a combobox
void OPMapGadgetWidget::loadComboBoxLines(QComboBox *comboBox, QString filename)
// move the magic waypoint {
if (!comboBox) return;
magic_waypoint.coord = destPoint(home_position.coord, bear, dist); if (filename.isNull() || filename.isEmpty()) return;
if (m_map_mode == MagicWaypoint_MapMode) QFile file(filename);
{ // move the on-screen waypoint if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
if (magic_waypoint.map_wp_item) return;
magic_waypoint.map_wp_item->SetCoord(magic_waypoint.coord);
} QTextStream in(&file);
}
while (!in.atEnd())
// ************************************************************************************* {
// return the distance between two points .. in kilometers QString line = in.readLine().simplified();
if (line.isNull() || line.isEmpty()) continue;
double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::PointLatLng to) comboBox->addItem(line);
{ }
double lat1 = from.Lat() * deg_to_rad;
double lon1 = from.Lng() * deg_to_rad; file.close();
}
double lat2 = to.Lat() * deg_to_rad;
double lon2 = to.Lng() * deg_to_rad; // save a combobox text contents to a simple text file
void OPMapGadgetWidget::saveComboBoxLines(QComboBox *comboBox, QString filename)
// *********************** {
// Haversine formula if (!comboBox) return;
/* if (filename.isNull() || filename.isEmpty()) return;
double delta_lat = lat2 - lat1;
double delta_lon = lon2 - lon1; QFile file(filename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
double t1 = sin(delta_lat / 2); return;
double t2 = sin(delta_lon / 2);
double a = (t1 * t1) + cos(lat1) * cos(lat2) * (t2 * t2); QTextStream out(&file);
double c = 2 * atan2(sqrt(a), sqrt(1 - a));
for (int i = 0; i < comboBox->count(); i++)
return (earth_mean_radius * c); {
*/ QString line = comboBox->itemText(i).simplified();
// *********************** if (line.isNull() || line.isEmpty()) continue;
// Spherical Law of Cosines out << line << "\n";
}
return (acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1)) * earth_mean_radius);
file.close();
// *********************** }
}
// *************************************************************************************
// ************************************************************************************* // show/hide the magic waypoint controls
// return the bearing from one point to another .. in degrees
void OPMapGadgetWidget::hideMagicWaypointControls()
double OPMapGadgetWidget::bearing(internals::PointLatLng from, internals::PointLatLng to) {
{ m_widget->lineWaypoint->setVisible(false);
double lat1 = from.Lat() * deg_to_rad; m_widget->toolButtonHomeWaypoint->setVisible(false);
double lon1 = from.Lng() * deg_to_rad; m_widget->toolButtonMoveToWP->setVisible(false);
}
double lat2 = to.Lat() * deg_to_rad;
double lon2 = to.Lng() * deg_to_rad; void OPMapGadgetWidget::showMagicWaypointControls()
{
// double delta_lat = lat2 - lat1; m_widget->lineWaypoint->setVisible(true);
double delta_lon = lon2 - lon1; m_widget->toolButtonHomeWaypoint->setVisible(true);
double y = sin(delta_lon) * cos(lat2); #if defined(allow_manual_home_location_move)
double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(delta_lon); m_widget->toolButtonMoveToWP->setVisible(true);
double bear = atan2(y, x) * rad_to_deg; #else
m_widget->toolButtonMoveToWP->setVisible(false);
bear += 360; #endif
while (bear < 0) bear += 360; }
while (bear >= 360) bear -= 360;
// *************************************************************************************
return bear; // move the magic waypoint to keep it within the safe area boundry
}
void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea()
// ************************************************************************************* {
// return a destination lat/lon point given a source lat/lon point and the bearing and distance from the source point
// calcute the bearing and distance from the home position to the magic waypoint
internals::PointLatLng OPMapGadgetWidget::destPoint(internals::PointLatLng source, double bear, double dist) double dist = distance(m_home_position.coord, m_magic_waypoint.coord);
{ double bear = bearing(m_home_position.coord, m_magic_waypoint.coord);
double lat1 = source.Lat() * deg_to_rad;
double lon1 = source.Lng() * deg_to_rad; // get the maximum safe distance - in kilometers
double boundry_dist = (double)m_map->Home->SafeArea() / 1000;
bear *= deg_to_rad;
// if (dist <= boundry_dist)
double ad = dist / earth_mean_radius; // return; // the magic waypoint is still within the safe area, don't move it
double lat2 = asin(sin(lat1) * cos(ad) + cos(lat1) * sin(ad) * cos(bear)); if (dist > boundry_dist) dist = boundry_dist;
double lon2 = lon1 + atan2(sin(bear) * sin(ad) * cos(lat1), cos(ad) - sin(lat1) * sin(lat2));
// move the magic waypoint
return internals::PointLatLng(lat2 * rad_to_deg, lon2 * rad_to_deg);
} m_magic_waypoint.coord = destPoint(m_home_position.coord, bear, dist);
// ************************************************************************************* if (m_map_mode == MagicWaypoint_MapMode)
{ // move the on-screen waypoint
bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, double &altitude) if (m_magic_waypoint.map_wp_item)
{ m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord);
double BaseECEF[3]; }
double NED[3]; }
double LLA[3];
UAVObject *obj; // *************************************************************************************
// return the distance between two points .. in kilometers
if (!obm)
return false; double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::PointLatLng to)
{
obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("HomeLocation"))); double lat1 = from.Lat() * deg_to_rad;
if (!obj) return false; double lon1 = from.Lng() * deg_to_rad;
BaseECEF[0] = obj->getField(QString("ECEF"))->getDouble(0) / 100;
BaseECEF[1] = obj->getField(QString("ECEF"))->getDouble(1) / 100; double lat2 = to.Lat() * deg_to_rad;
BaseECEF[2] = obj->getField(QString("ECEF"))->getDouble(2) / 100; double lon2 = to.Lng() * deg_to_rad;
obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("PositionActual"))); // ***********************
if (!obj) return false; // Haversine formula
NED[0] = obj->getField(QString("North"))->getDouble() / 100; /*
NED[1] = obj->getField(QString("East"))->getDouble() / 100; double delta_lat = lat2 - lat1;
NED[2] = obj->getField(QString("Down"))->getDouble() / 100; double delta_lon = lon2 - lon1;
// obj = dynamic_cast<UAVDataObject*>(om->getObject(QString("PositionDesired"))); double t1 = sin(delta_lat / 2);
double t2 = sin(delta_lon / 2);
// obj = dynamic_cast<UAVDataObject*>(objManager->getObject("VelocityActual")); // air speed double a = (t1 * t1) + cos(lat1) * cos(lat2) * (t2 * t2);
double c = 2 * atan2(sqrt(a), sqrt(1 - a));
Utils::CoordinateConversions().GetLLA(BaseECEF, NED, LLA);
return (earth_mean_radius * c);
latitude = LLA[0]; */
longitude = LLA[1]; // ***********************
altitude = LLA[2]; // Spherical Law of Cosines
if (latitude != latitude) latitude = 0; // nan detection return (acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1)) * earth_mean_radius);
// if (isNan(latitude)) latitude = 0; // nan detection
else // ***********************
// if (!isFinite(latitude)) latitude = 0; }
// else
if (latitude > 90) latitude = 90; // *************************************************************************************
else // return the bearing from one point to another .. in degrees
if (latitude < -90) latitude = -90;
double OPMapGadgetWidget::bearing(internals::PointLatLng from, internals::PointLatLng to)
if (longitude != longitude) longitude = 0; // nan detection {
else double lat1 = from.Lat() * deg_to_rad;
// if (longitude > std::numeric_limits<double>::max()) longitude = 0; // +infinite double lon1 = from.Lng() * deg_to_rad;
// else
// if (longitude < -std::numeric_limits<double>::max()) longitude = 0; // -infinite double lat2 = to.Lat() * deg_to_rad;
// else double lon2 = to.Lng() * deg_to_rad;
if (longitude > 180) longitude = 180;
else // double delta_lat = lat2 - lat1;
if (longitude < -180) longitude = -180; double delta_lon = lon2 - lon1;
if (altitude != altitude) altitude = 0; // nan detection double y = sin(delta_lon) * cos(lat2);
double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(delta_lon);
return true; double bear = atan2(y, x) * rad_to_deg;
}
bear += 360;
// ************************************************************************************* while (bear < 0) bear += 360;
while (bear >= 360) bear -= 360;
bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude)
{ return bear;
double LLA[3]; }
if (!obum) // *************************************************************************************
return false; // return a destination lat/lon point given a source lat/lon point and the bearing and distance from the source point
if (obum->getGPSPosition(LLA) < 0) internals::PointLatLng OPMapGadgetWidget::destPoint(internals::PointLatLng source, double bear, double dist)
return false; // error {
double lat1 = source.Lat() * deg_to_rad;
latitude = LLA[0]; double lon1 = source.Lng() * deg_to_rad;
longitude = LLA[1];
altitude = LLA[2]; bear *= deg_to_rad;
return true; double ad = dist / earth_mean_radius;
}
double lat2 = asin(sin(lat1) * cos(ad) + cos(lat1) * sin(ad) * cos(bear));
double OPMapGadgetWidget::getUAV_Yaw() double lon2 = lon1 + atan2(sin(bear) * sin(ad) * cos(lat1), cos(ad) - sin(lat1) * sin(lat2));
{
if (!obm) return internals::PointLatLng(lat2 * rad_to_deg, lon2 * rad_to_deg);
return 0; }
UAVObject *obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("AttitudeActual"))); // *************************************************************************************
double yaw = obj->getField(QString("Yaw"))->getDouble();
bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, double &altitude)
if (yaw != yaw) yaw = 0; // nan detection {
double BaseECEF[3];
while (yaw < 0) yaw += 360; double NED[3];
while (yaw >= 360) yaw -= 360; double LLA[3];
UAVObject *obj;
return yaw;
} if (!obm)
return false;
// *************************************************************************************
obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("HomeLocation")));
void OPMapGadgetWidget::setMapFollowingMode() if (!obj) return false;
{ BaseECEF[0] = obj->getField(QString("ECEF"))->getDouble(0) / 100;
if (!m_widget || !m_map) BaseECEF[1] = obj->getField(QString("ECEF"))->getDouble(1) / 100;
return; BaseECEF[2] = obj->getField(QString("ECEF"))->getDouble(2) / 100;
if (!followUAVpositionAct->isChecked()) obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("PositionActual")));
{ if (!obj) return false;
m_map->UAV->SetMapFollowType(UAVMapFollowType::None); NED[0] = obj->getField(QString("North"))->getDouble() / 100;
m_map->SetRotate(0); // reset map rotation to 0deg NED[1] = obj->getField(QString("East"))->getDouble() / 100;
} NED[2] = obj->getField(QString("Down"))->getDouble() / 100;
else
if (!followUAVheadingAct->isChecked()) // obj = dynamic_cast<UAVDataObject*>(om->getObject(QString("PositionDesired")));
{
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // obj = dynamic_cast<UAVDataObject*>(objManager->getObject("VelocityActual")); // air speed
m_map->SetRotate(0); // reset map rotation to 0deg
} Utils::CoordinateConversions().GetLLA(BaseECEF, NED, LLA);
else
{ latitude = LLA[0];
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode longitude = LLA[1];
altitude = LLA[2];
m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap); if (latitude != latitude) latitude = 0; // nan detection
} // if (isNan(latitude)) latitude = 0; // nan detection
} else
// if (!isFinite(latitude)) latitude = 0;
// ************************************************************************************* // else
// update the HomeLocation UAV Object if (latitude > 90) latitude = 90;
else
bool OPMapGadgetWidget::setHomeLocationObject() if (latitude < -90) latitude = -90;
{
if (!obum) if (longitude != longitude) longitude = 0; // nan detection
return false; else
// if (longitude > std::numeric_limits<double>::max()) longitude = 0; // +infinite
double LLA[3] = {home_position.coord.Lat(), home_position.coord.Lng(), home_position.altitude}; // else
return (obum->setHomeLocation(LLA, true) >= 0); // if (longitude < -std::numeric_limits<double>::max()) longitude = 0; // -infinite
} // else
if (longitude > 180) longitude = 180;
// ************************************************************************************* else
if (longitude < -180) longitude = -180;
void OPMapGadgetWidget::SetUavPic(QString UAVPic)
{ if (altitude != altitude) altitude = 0; // nan detection
m_map->SetUavPic(UAVPic);
} return true;
}
double OPMapGadgetWidget::getUAV_Yaw()
{
if (!obm)
return 0;
UAVObject *obj = dynamic_cast<UAVDataObject*>(obm->getObject(QString("AttitudeActual")));
double yaw = obj->getField(QString("Yaw"))->getDouble();
if (yaw != yaw) yaw = 0; // nan detection
while (yaw < 0) yaw += 360;
while (yaw >= 360) yaw -= 360;
return yaw;
}
bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude)
{
double LLA[3];
if (!obum)
return false;
if (obum->getGPSPosition(LLA) < 0)
return false; // error
latitude = LLA[0];
longitude = LLA[1];
altitude = LLA[2];
return true;
}
// *************************************************************************************
void OPMapGadgetWidget::setMapFollowingMode()
{
if (!m_widget || !m_map)
return;
if (!followUAVpositionAct->isChecked())
{
m_map->UAV->SetMapFollowType(UAVMapFollowType::None);
m_map->SetRotate(0); // reset map rotation to 0deg
}
else
if (!followUAVheadingAct->isChecked())
{
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap);
m_map->SetRotate(0); // reset map rotation to 0deg
}
else
{
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode
m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg
m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap);
}
}
// *************************************************************************************
// update the HomeLocation UAV Object
bool OPMapGadgetWidget::setHomeLocationObject()
{
if (!obum)
return false;
double LLA[3] = {m_home_position.coord.Lat(), m_home_position.coord.Lng(), m_home_position.altitude};
return (obum->setHomeLocation(LLA, true) >= 0);
}
// *************************************************************************************
void OPMapGadgetWidget::SetUavPic(QString UAVPic)
{
m_map->SetUavPic(UAVPic);
}

View File

@ -1,347 +1,361 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file opmapgadgetwidget.h * @file opmapgadgetwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins * @addtogroup GCSPlugins GCS Plugins
* @{ * @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin * @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{ * @{
* @brief The OpenPilot Map plugin * @brief The OpenPilot Map plugin
*****************************************************************************/ *****************************************************************************/
/* /*
* This program is free software; you can redistribute it and/or modify * This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or * the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* This program is distributed in the hope that it will be useful, but * This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details. * for more details.
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc., * with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#ifndef OPMAP_GADGETWIDGET_H_ #ifndef OPMAP_GADGETWIDGET_H_
#define OPMAP_GADGETWIDGET_H_ #define OPMAP_GADGETWIDGET_H_
// ****************************************************** // ******************************************************
#include <QtGui/QWidget> #include <QtGui/QWidget>
#include <QtGui/QMenu> #include <QtGui/QMenu>
#include <QStringList> #include <QStringList>
#include <QStandardItemModel> #include <QStandardItemModel>
#include <QList> #include <QList>
#include <QMutex> #include <QMutex>
#include <QMutexLocker> #include <QMutexLocker>
#include <QPointF> #include <QPointF>
#include "opmapcontrol/opmapcontrol.h" #include "opmapcontrol/opmapcontrol.h"
#include "opmap_overlay_widget.h" #include "opmap_overlay_widget.h"
#include "opmap_zoom_slider_widget.h" #include "opmap_zoom_slider_widget.h"
#include "opmap_statusbar_widget.h" #include "opmap_statusbar_widget.h"
#include "utils/coordinateconversions.h" #include "utils/coordinateconversions.h"
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include "uavobjectutilmanager.h" #include "uavobjectutilmanager.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"
#include "uavobject.h" #include "uavobject.h"
#include "objectpersistence.h" #include "objectpersistence.h"
// ****************************************************** // ******************************************************
namespace Ui namespace Ui
{ {
class OPMap_Widget; class OPMap_Widget;
} }
using namespace mapcontrol; using namespace mapcontrol;
// ****************************************************** // ******************************************************
typedef struct t_home typedef struct t_home
{ {
internals::PointLatLng coord; internals::PointLatLng coord;
double altitude; double altitude;
bool locked; bool locked;
} t_home; } t_home;
// local waypoint list item structure // local waypoint list item structure
typedef struct t_waypoint typedef struct t_waypoint
{ {
mapcontrol::WayPointItem *map_wp_item; mapcontrol::WayPointItem *map_wp_item;
internals::PointLatLng coord; internals::PointLatLng coord;
double altitude; double altitude;
QString description; QString description;
bool locked; bool locked;
int time_seconds; int time_seconds;
int hold_time_seconds; int hold_time_seconds;
} t_waypoint; } t_waypoint;
// ****************************************************** // ******************************************************
enum opMapModeType { Normal_MapMode = 0, enum opMapModeType { Normal_MapMode = 0,
MagicWaypoint_MapMode = 1}; MagicWaypoint_MapMode = 1};
// ****************************************************** // ******************************************************
class OPMapGadgetWidget : public QWidget class OPMapGadgetWidget : public QWidget
{ {
Q_OBJECT Q_OBJECT
public: public:
OPMapGadgetWidget(QWidget *parent = 0); OPMapGadgetWidget(QWidget *parent = 0);
~OPMapGadgetWidget(); ~OPMapGadgetWidget();
/** /**
* @brief public functions * @brief public functions
* *
* @param * @param
*/ */
void setHome(QPointF pos); void setHome(QPointF pos);
void setHome(internals::PointLatLng pos_lat_lon); void setHome(internals::PointLatLng pos_lat_lon);
void goHome(); void goHome();
void setZoom(int zoom); void setZoom(int zoom);
void setPosition(QPointF pos); void setPosition(QPointF pos);
void setMapProvider(QString provider); void setMapProvider(QString provider);
void setUseOpenGL(bool useOpenGL); void setUseOpenGL(bool useOpenGL);
void setShowTileGridLines(bool showTileGridLines); void setShowTileGridLines(bool showTileGridLines);
void setAccessMode(QString accessMode); void setAccessMode(QString accessMode);
void setUseMemoryCache(bool useMemoryCache); void setUseMemoryCache(bool useMemoryCache);
void setCacheLocation(QString cacheLocation); void setCacheLocation(QString cacheLocation);
void setMapMode(opMapModeType mode); void setMapMode(opMapModeType mode);
void SetUavPic(QString UAVPic); void SetUavPic(QString UAVPic);
void setMaxUpdateRate(int update_rate);
public slots:
void homePositionUpdated(UAVObject *); public slots:
void onTelemetryConnect(); void homePositionUpdated(UAVObject *);
void onTelemetryDisconnect(); void onTelemetryConnect();
void onTelemetryDisconnect();
protected:
void resizeEvent(QResizeEvent *event); protected:
void mouseMoveEvent(QMouseEvent *event); void resizeEvent(QResizeEvent *event);
void contextMenuEvent(QContextMenuEvent *event); void mouseMoveEvent(QMouseEvent *event);
void keyPressEvent(QKeyEvent* event); void contextMenuEvent(QContextMenuEvent *event);
void keyPressEvent(QKeyEvent* event);
private slots:
void updatePosition(); private slots:
void updatePosition();
void updateMousePos();
void updateMousePos();
void zoomIn();
void zoomOut(); void zoomIn();
void zoomOut();
/**
* @brief signals received from the various map plug-in widget user controls /**
* * @brief signals received from the various map plug-in widget user controls
* Some are currently disabled for the v1.0 plugin version. *
*/ * Some are currently disabled for the v1.0 plugin version.
// void comboBoxFindPlace_returnPressed(); */
// void on_toolButtonFindPlace_clicked(); // void comboBoxFindPlace_returnPressed();
void on_toolButtonZoomM_clicked(); // void on_toolButtonFindPlace_clicked();
void on_toolButtonZoomP_clicked(); void on_toolButtonZoomM_clicked();
void on_toolButtonMapHome_clicked(); void on_toolButtonZoomP_clicked();
void on_toolButtonMapUAV_clicked(); void on_toolButtonMapHome_clicked();
void on_toolButtonMapUAVheading_clicked(); void on_toolButtonMapUAV_clicked();
void on_horizontalSliderZoom_sliderMoved(int position); void on_toolButtonMapUAVheading_clicked();
// void on_toolButtonAddWaypoint_clicked(); void on_horizontalSliderZoom_sliderMoved(int position);
// void on_treeViewWaypoints_clicked(QModelIndex index); // void on_toolButtonAddWaypoint_clicked();
// void on_toolButtonHome_clicked(); // void on_treeViewWaypoints_clicked(QModelIndex index);
// void on_toolButtonNextWaypoint_clicked(); // void on_toolButtonHome_clicked();
// void on_toolButtonPrevWaypoint_clicked(); // void on_toolButtonNextWaypoint_clicked();
// void on_toolButtonHoldPosition_clicked(); // void on_toolButtonPrevWaypoint_clicked();
// void on_toolButtonGo_clicked(); // void on_toolButtonHoldPosition_clicked();
void on_toolButtonMagicWaypointMapMode_clicked(); // void on_toolButtonGo_clicked();
void on_toolButtonNormalMapMode_clicked(); void on_toolButtonMagicWaypointMapMode_clicked();
void on_toolButtonHomeWaypoint_clicked(); void on_toolButtonNormalMapMode_clicked();
void on_toolButtonMoveToWP_clicked(); void on_toolButtonHomeWaypoint_clicked();
void on_toolButtonMoveToWP_clicked();
/**
* @brief signals received from the map object /**
*/ * @brief signals received from the map object
void zoomChanged(double zoomt,double zoom, double zoomd); */
void OnCurrentPositionChanged(internals::PointLatLng point); void zoomChanged(double zoomt,double zoom, double zoomd);
void OnTileLoadComplete(); void OnCurrentPositionChanged(internals::PointLatLng point);
void OnTileLoadStart(); void OnTileLoadComplete();
void OnMapDrag(); void OnTileLoadStart();
void OnMapZoomChanged(); void OnMapDrag();
void OnMapTypeChanged(MapType::Types type); void OnMapZoomChanged();
void OnEmptyTileError(int zoom, core::Point pos); void OnMapTypeChanged(MapType::Types type);
void OnTilesStillToLoad(int number); void OnEmptyTileError(int zoom, core::Point pos);
void OnTilesStillToLoad(int number);
/**
* Unused for now, hooks for future waypoint support /**
*/ * Unused for now, hooks for future waypoint support
void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); */
void WPValuesChanged(WayPointItem* waypoint); void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint);
void WPInserted(int const& number, WayPointItem* waypoint); void WPValuesChanged(WayPointItem* waypoint);
void WPDeleted(int const& number); void WPInserted(int const& number, WayPointItem* waypoint);
void WPDeleted(int const& number);
/**
* @brief mouse right click context menu signals /**
*/ * @brief mouse right click context menu signals
void onReloadAct_triggered(); */
void onCopyMouseLatLonToClipAct_triggered(); void onReloadAct_triggered();
void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLatLonToClipAct_triggered();
void onCopyMouseLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered();
// void onFindPlaceAct_triggered(); void onCopyMouseLonToClipAct_triggered();
void onShowCompassAct_toggled(bool show); // void onFindPlaceAct_triggered();
void onShowDiagnostics_toggled(bool show); void onShowCompassAct_toggled(bool show);
void onShowUAVAct_toggled(bool show); void onShowDiagnostics_toggled(bool show);
void onShowHomeAct_toggled(bool show); void onShowUAVAct_toggled(bool show);
void onShowTrailLineAct_toggled(bool show); void onShowHomeAct_toggled(bool show);
void onShowTrailAct_toggled(bool show); void onShowTrailLineAct_toggled(bool show);
void onGoZoomInAct_triggered(); void onShowTrailAct_toggled(bool show);
void onGoZoomOutAct_triggered(); void onGoZoomInAct_triggered();
void onGoMouseClickAct_triggered(); void onGoZoomOutAct_triggered();
void onSetHomeAct_triggered(); void onGoMouseClickAct_triggered();
void onGoHomeAct_triggered(); void onSetHomeAct_triggered();
void onGoUAVAct_triggered(); void onGoHomeAct_triggered();
void onFollowUAVpositionAct_toggled(bool checked); void onGoUAVAct_triggered();
void onFollowUAVheadingAct_toggled(bool checked); void onFollowUAVpositionAct_toggled(bool checked);
/* void onFollowUAVheadingAct_toggled(bool checked);
void onOpenWayPointEditorAct_triggered(); /*
void onAddWayPointAct_triggered(); void onOpenWayPointEditorAct_triggered();
void onEditWayPointAct_triggered(); void onAddWayPointAct_triggered();
void onLockWayPointAct_triggered(); void onEditWayPointAct_triggered();
void onDeleteWayPointAct_triggered(); void onLockWayPointAct_triggered();
void onClearWayPointsAct_triggered(); void onDeleteWayPointAct_triggered();
*/ void onClearWayPointsAct_triggered();
void onMapModeActGroup_triggered(QAction *action); */
void onZoomActGroup_triggered(QAction *action); void onMapModeActGroup_triggered(QAction *action);
void onHomeMagicWaypointAct_triggered(); void onZoomActGroup_triggered(QAction *action);
void onShowSafeAreaAct_toggled(bool show); void onHomeMagicWaypointAct_triggered();
void onSafeAreaActGroup_triggered(QAction *action); void onShowSafeAreaAct_toggled(bool show);
void onUAVTrailTypeActGroup_triggered(QAction *action); void onSafeAreaActGroup_triggered(QAction *action);
void onClearUAVtrailAct_triggered(); void onUAVTrailTypeActGroup_triggered(QAction *action);
void onUAVTrailTimeActGroup_triggered(QAction *action); void onClearUAVtrailAct_triggered();
void onUAVTrailDistanceActGroup_triggered(QAction *action); void onUAVTrailTimeActGroup_triggered(QAction *action);
void onUAVTrailDistanceActGroup_triggered(QAction *action);
private: void onMaxUpdateRateActGroup_triggered(QAction *action);
int min_zoom;
int max_zoom; private:
double m_heading; // uav heading // *****
internals::PointLatLng mouse_lat_lon; int m_min_zoom;
internals::PointLatLng context_menu_lat_lon; int m_max_zoom;
int prev_tile_number; double m_heading; // uav heading
opMapModeType m_map_mode; internals::PointLatLng m_mouse_lat_lon;
internals::PointLatLng m_context_menu_lat_lon;
t_home home_position;
int m_prev_tile_number;
t_waypoint magic_waypoint;
opMapModeType m_map_mode;
QStringList findPlaceWordList;
QCompleter *findPlaceCompleter; int m_maxUpdateRate;
QTimer *m_updateTimer; t_home m_home_position;
QTimer *m_statusUpdateTimer;
t_waypoint m_magic_waypoint;
Ui::OPMap_Widget *m_widget;
QStringList findPlaceWordList;
mapcontrol::OPMapWidget *m_map; QCompleter *findPlaceCompleter;
ExtensionSystem::PluginManager *pm; QTimer *m_updateTimer;
UAVObjectManager *obm; QTimer *m_statusUpdateTimer;
UAVObjectUtilManager *obum;
Ui::OPMap_Widget *m_widget;
//opmap_waypointeditor_dialog waypoint_editor_dialog;
mapcontrol::OPMapWidget *m_map;
//opmap_edit_waypoint_dialog waypoint_edit_dialog;
ExtensionSystem::PluginManager *pm;
QStandardItemModel wayPoint_treeView_model; UAVObjectManager *obm;
UAVObjectUtilManager *obum;
mapcontrol::WayPointItem *m_mouse_waypoint;
//opmap_waypointeditor_dialog waypoint_editor_dialog;
QList<t_waypoint *> m_waypoint_list;
QMutex m_waypoint_list_mutex; //opmap_edit_waypoint_dialog waypoint_edit_dialog;
QMutex m_map_mutex; QStandardItemModel wayPoint_treeView_model;
bool telemetry_connected; mapcontrol::WayPointItem *m_mouse_waypoint;
void createActions(); QList<t_waypoint *> m_waypoint_list;
QMutex m_waypoint_list_mutex;
QAction *closeAct1;
QAction *closeAct2; QMutex m_map_mutex;
QAction *reloadAct;
QAction *copyMouseLatLonToClipAct; bool m_telemetry_connected;
QAction *copyMouseLatToClipAct;
QAction *copyMouseLonToClipAct; // *****
QAction *findPlaceAct;
QAction *showCompassAct; void createActions();
QAction *showDiagnostics;
QAction *showHomeAct; QAction *closeAct1;
QAction *showUAVAct; QAction *closeAct2;
QAction *zoomInAct; QAction *reloadAct;
QAction *zoomOutAct; QAction *copyMouseLatLonToClipAct;
QAction *goMouseClickAct; QAction *copyMouseLatToClipAct;
QAction *setHomeAct; QAction *copyMouseLonToClipAct;
QAction *goHomeAct; QAction *findPlaceAct;
QAction *goUAVAct; QAction *showCompassAct;
QAction *followUAVpositionAct; QAction *showDiagnostics;
QAction *followUAVheadingAct; QAction *showHomeAct;
/* QAction *showUAVAct;
QAction *wayPointEditorAct; QAction *zoomInAct;
QAction *addWayPointAct; QAction *zoomOutAct;
QAction *editWayPointAct; QAction *goMouseClickAct;
QAction *lockWayPointAct; QAction *setHomeAct;
QAction *deleteWayPointAct; QAction *goHomeAct;
QAction *clearWayPointsAct; QAction *goUAVAct;
*/ QAction *followUAVpositionAct;
QAction *homeMagicWaypointAct; QAction *followUAVheadingAct;
/*
QAction *showSafeAreaAct; QAction *wayPointEditorAct;
QActionGroup *safeAreaActGroup; QAction *addWayPointAct;
QList<QAction *> safeAreaAct; QAction *editWayPointAct;
QAction *lockWayPointAct;
QActionGroup *uavTrailTypeActGroup; QAction *deleteWayPointAct;
QList<QAction *> uavTrailTypeAct; QAction *clearWayPointsAct;
QAction *clearUAVtrailAct; */
QActionGroup *uavTrailTimeActGroup; QAction *homeMagicWaypointAct;
QAction *showTrailLineAct;
QAction *showTrailAct; QAction *showSafeAreaAct;
QList<QAction *> uavTrailTimeAct; QActionGroup *safeAreaActGroup;
QActionGroup *uavTrailDistanceActGroup; QList<QAction *> safeAreaAct;
QList<QAction *> uavTrailDistanceAct;
QActionGroup *uavTrailTypeActGroup;
QActionGroup *mapModeActGroup; QList<QAction *> uavTrailTypeAct;
QList<QAction *> mapModeAct; QAction *clearUAVtrailAct;
QActionGroup *uavTrailTimeActGroup;
QActionGroup *zoomActGroup; QAction *showTrailLineAct;
QList<QAction *> zoomAct; QAction *showTrailAct;
QList<QAction *> uavTrailTimeAct;
void homeMagicWaypoint(); QActionGroup *uavTrailDistanceActGroup;
QList<QAction *> uavTrailDistanceAct;
void moveToMagicWaypointPosition();
QActionGroup *mapModeActGroup;
void loadComboBoxLines(QComboBox *comboBox, QString filename); QList<QAction *> mapModeAct;
void saveComboBoxLines(QComboBox *comboBox, QString filename);
QActionGroup *zoomActGroup;
void hideMagicWaypointControls(); QList<QAction *> zoomAct;
void showMagicWaypointControls();
QActionGroup *maxUpdateRateActGroup;
void keepMagicWaypointWithInSafeArea(); QList<QAction *> maxUpdateRateAct;
double distance(internals::PointLatLng from, internals::PointLatLng to); // *****
double bearing(internals::PointLatLng from, internals::PointLatLng to);
internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist); void homeMagicWaypoint();
bool getUAVPosition(double &latitude, double &longitude, double &altitude); void moveToMagicWaypointPosition();
bool getGPSPosition(double &latitude, double &longitude, double &altitude);
double getUAV_Yaw(); void loadComboBoxLines(QComboBox *comboBox, QString filename);
void saveComboBoxLines(QComboBox *comboBox, QString filename);
void setMapFollowingMode();
void hideMagicWaypointControls();
bool setHomeLocationObject(); void showMagicWaypointControls();
};
void keepMagicWaypointWithInSafeArea();
#endif /* OPMAP_GADGETWIDGET_H_ */
double distance(internals::PointLatLng from, internals::PointLatLng to);
double bearing(internals::PointLatLng from, internals::PointLatLng to);
internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist);
bool getUAVPosition(double &latitude, double &longitude, double &altitude);
bool getGPSPosition(double &latitude, double &longitude, double &altitude);
double getUAV_Yaw();
void setMapFollowingMode();
bool setHomeLocationObject();
};
#endif /* OPMAP_GADGETWIDGET_H_ */

View File

@ -151,6 +151,16 @@ void SystemHealthGadgetWidget::setSystemFile(QString dfn)
QGraphicsScene *l_scene = scene(); QGraphicsScene *l_scene = scene();
l_scene->setSceneRect(background->boundingRect()); l_scene->setSceneRect(background->boundingRect());
fitInView(background, Qt::KeepAspectRatio ); fitInView(background, Qt::KeepAspectRatio );
// Check whether the autopilot is connected already, by the way:
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
if (telMngr->isConnected()) {
onAutopilotConnect();
SystemAlarms* obj = dynamic_cast<SystemAlarms*>(objManager->getObject(QString("SystemAlarms")));
updateAlarms(obj);
}
} }
} }
else else

View File

@ -4,7 +4,7 @@
<field name="AccelBias" units="lsb" type="int16" elementnames="X,Y,Z" defaultvalue="0"/> <field name="AccelBias" units="lsb" type="int16" elementnames="X,Y,Z" defaultvalue="0"/>
<field name="BoardRotation" units="deg" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/> <field name="BoardRotation" units="deg" type="int8" elementnames="Roll,Pitch,Yaw" defaultvalue="0,0,0"/>
<field name="GyroGain" units="(rad/s)/lsb" type="float" elements="1" defaultvalue="0.42"/> <field name="GyroGain" units="(rad/s)/lsb" type="float" elements="1" defaultvalue="0.42"/>
<field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.01"/> <field name="AccelKp" units="channel" type="float" elements="1" defaultvalue="0.05"/>
<field name="AccelKi" units="channel" type="float" elements="1" defaultvalue="0.0001"/> <field name="AccelKi" units="channel" type="float" elements="1" defaultvalue="0.0001"/>
<field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/> <field name="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
<field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/> <field name="ZeroDuringArming" units="channel" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>

View File

@ -7,9 +7,9 @@
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/> <field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/> <field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/>
<field name="RollRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.3"/> <field name="RollRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.002,0,0.3"/>
<field name="PitchRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.3"/> <field name="PitchRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.002,0,0.3"/>
<field name="YawRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.003,0,0.3"/> <field name="YawRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.003,0.003,0.3"/>
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/> <field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/> <field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/> <field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>