1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-19 09: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
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
C: ?
D: ?

View File

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

View File

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

View File

@ -678,8 +678,10 @@ void PIOS_Board_Init(void) {
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_FLASHFS_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */

View File

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

View File

@ -30,6 +30,7 @@
#include "openpilot.h"
#include "firmwareiap.h"
#include "firmwareiapobj.h"
#include "flightstatus.h"
// Private constants
#define IAP_CMD_STEP_1 1122
@ -156,6 +157,16 @@ static void FirmwareIAPCallback(UAVObjEvent* ev)
case IAP_STATE_STEP_2:
if( data.Command == IAP_CMD_STEP_3 ) {
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 time requirements.
PIOS_IAP_SetRequest1();

View File

@ -63,7 +63,7 @@ static float GravityAccel(float latitude, float longitude, float altitude);
// Private constants
//#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_COMMAND_RESEND_TIMEOUT_MS 2000
@ -154,7 +154,7 @@ static void gpsTask(void *parameters)
}
#endif
#ifdef DISABLE_GPS_TRESHOLD
#ifdef DISABLE_GPS_THRESHOLD
PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n");
#endif

View File

@ -52,14 +52,13 @@ endif
FLASH_TOOL = OPENOCD
# 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 MK/MKSerial
#MODULES = Telemetry
#MODULES += Osd/OsdEtStd
# MCU name, submodel and board
# - MCU used for compiler-option (-mcpu)
# - 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.)
# use file-extension c for "c-only"-files
MODNAMES = $(notdir ${MODULES})
MODNAMES = $(notdir ${MODULES} ${PYMODULES})
ifndef TESTAPP
## PyMite files
## PyMite files and modules
SRC += $(OUTDIR)/pmlib_img.c
SRC += $(OUTDIR)/pmlib_nat.c
SRC += $(OUTDIR)/pmlibusr_img.c
SRC += $(OUTDIR)/pmlibusr_nat.c
SRC += $(wildcard ${PYMITEVM}/*.c)
SRC += $(wildcard ${PYMITEPLAT}/*.c)
PYSRC += $(wildcard ${PYMITEVM}/*.c)
PYSRC += $(wildcard ${PYMITEPLAT}/*.c)
PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
SRC += $(PYSRC)
## MODULES
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
@ -317,7 +318,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
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.
@ -481,7 +482,7 @@ LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
# Default target.
all: gencode gccversion build
all: gccversion build
ifeq ($(LOADFORMAT),ihex)
build: elf hex lss sym
@ -500,6 +501,8 @@ endif
# 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
$(PYSRC): gencode
# Generate code for module initialization
${OUTDIR}/InitMods.c: Makefile
@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;
}
/**
* @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)
{
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
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main PiOS header.
* - Central header for the project.
* @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
*/
#ifndef PIOS_H
#define PIOS_H
/* PIOS Feature Selection */
#include "pios_config.h"
#if defined(PIOS_INCLUDE_FREERTOS)
/* FreeRTOS Includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
#endif
/* C Lib Includes */
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>
#include <math.h>
/* STM32 Std Perf Lib */
#include <stm32f10x.h>
#include <stm32f10x_conf.h>
#if defined(PIOS_INCLUDE_SDCARD)
/* Dosfs Includes */
#include <dosfs.h>
/* Mass Storage Device Includes */
#include <msd.h>
#endif
/* Generic initcall infrastructure */
#include "pios_initcall.h"
/* PIOS Board Specific Device Configuration */
#include "pios_board.h"
/* PIOS Hardware Includes (STM32F10x) */
#include <pios_sys.h>
#include <pios_delay.h>
#include <pios_led.h>
#include <pios_sdcard.h>
#include <pios_usart.h>
#include <pios_irq.h>
#include <pios_adc.h>
#include <pios_servo.h>
#include <pios_i2c.h>
#include <pios_spi.h>
#include <pios_ppm.h>
#include <pios_pwm.h>
#include <pios_spektrum.h>
#include <pios_usb_hid.h>
#include <pios_debug.h>
#include <pios_gpio.h>
#if defined(PIOS_INCLUDE_EXTI)
#include <pios_exti.h>
#endif
#include <pios_wdg.h>
/* PIOS Hardware Includes (Common) */
#include <pios_sdcard.h>
#include <pios_com.h>
#if defined(PIOS_INCLUDE_BMP085)
#include <pios_bmp085.h>
#endif
#if defined(PIOS_INCLUDE_HCSR04)
#include <pios_hcsr04.h>
#endif
#if defined(PIOS_INCLUDE_HMC5843)
#include <pios_hmc5843.h>
#endif
#if defined(PIOS_INCLUDE_HMC5883)
#include <pios_hmc5883.h>
#endif
#if defined(PIOS_INCLUDE_I2C_ESC)
#include <pios_i2c_esc.h>
#endif
#if defined(PIOS_INCLUDE_IMU3000)
#include <pios_imu3000.h>
#endif
#include <pios_iap.h>
#if defined(PIOS_INCLUDE_ADXL345)
#include <pios_adxl345.h>
#endif
#if defined(PIOS_INCLUDE_BMA180)
#include <pios_bma180.h>
#endif
#if defined(PIOS_INCLUDE_FLASH)
#include <pios_flash_w25x.h>
#endif
#if defined(PIOS_INCLUDE_BL_HELPER)
#include <pios_bl_helper.h>
#endif
#if defined(PIOS_INCLUDE_USB)
/* USB Libs */
#include <usb_lib.h>
#endif
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
#endif /* PIOS_H */
/**
******************************************************************************
*
* @file pios.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main PiOS header.
* - Central header for the project.
* @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
*/
#ifndef PIOS_H
#define PIOS_H
/* PIOS Feature Selection */
#include "pios_config.h"
#if defined(PIOS_INCLUDE_FREERTOS)
/* FreeRTOS Includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
#endif
/* C Lib Includes */
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>
#include <math.h>
/* STM32 Std Perf Lib */
#include <stm32f10x.h>
#include <stm32f10x_conf.h>
#if defined(PIOS_INCLUDE_SDCARD)
/* Dosfs Includes */
#include <dosfs.h>
/* Mass Storage Device Includes */
#include <msd.h>
#endif
/* Generic initcall infrastructure */
#include "pios_initcall.h"
/* PIOS Board Specific Device Configuration */
#include "pios_board.h"
/* PIOS Hardware Includes (STM32F10x) */
#include <pios_sys.h>
#include <pios_delay.h>
#include <pios_led.h>
#include <pios_sdcard.h>
#include <pios_usart.h>
#include <pios_irq.h>
#include <pios_adc.h>
#include <pios_servo.h>
#include <pios_i2c.h>
#include <pios_spi.h>
#include <pios_ppm.h>
#include <pios_pwm.h>
#include <pios_spektrum.h>
#include <pios_usb_hid.h>
#include <pios_debug.h>
#include <pios_gpio.h>
#if defined(PIOS_INCLUDE_EXTI)
#include <pios_exti.h>
#endif
#include <pios_wdg.h>
/* PIOS Hardware Includes (Common) */
#include <pios_sdcard.h>
#include <pios_com.h>
#if defined(PIOS_INCLUDE_BMP085)
#include <pios_bmp085.h>
#endif
#if defined(PIOS_INCLUDE_HCSR04)
#include <pios_hcsr04.h>
#endif
#if defined(PIOS_INCLUDE_HMC5843)
#include <pios_hmc5843.h>
#endif
#if defined(PIOS_INCLUDE_HMC5883)
#include <pios_hmc5883.h>
#endif
#if defined(PIOS_INCLUDE_I2C_ESC)
#include <pios_i2c_esc.h>
#endif
#if defined(PIOS_INCLUDE_IMU3000)
#include <pios_imu3000.h>
#endif
#include <pios_iap.h>
#if defined(PIOS_INCLUDE_ADXL345)
#include <pios_adxl345.h>
#endif
#if defined(PIOS_INCLUDE_BMA180)
#include <pios_bma180.h>
#endif
#if defined(PIOS_INCLUDE_FLASH)
#include <pios_flash_w25x.h>
#include <pios_flashfs_objlist.h>
#endif
#if defined(PIOS_INCLUDE_BL_HELPER)
#include <pios_bl_helper.h>
#endif
#if defined(PIOS_INCLUDE_USB)
/* USB Libs */
#include <usb_lib.h>
#endif
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
#endif /* PIOS_H */

View File

@ -3171,6 +3171,8 @@
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>"; };
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 */
/* Begin PBXGroup section */
@ -7657,6 +7659,7 @@
65E8F03711EFF25C00BBF654 /* printf-stdarg.c */,
6528CCB412E406B800CF5144 /* pios_adxl345.c */,
6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */,
65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */,
);
name = Common;
path = ../../PiOS/Common;
@ -7681,6 +7684,7 @@
65E8F03E11EFF25C00BBF654 /* pios_debug.h */,
65E8F03F11EFF25C00BBF654 /* pios_delay.h */,
65E8F04011EFF25C00BBF654 /* pios_exti.h */,
65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */,
65E8F04111EFF25C00BBF654 /* pios_gpio.h */,
65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */,
65E8F04311EFF25C00BBF654 /* pios_i2c.h */,

View File

@ -1,1607 +1,1498 @@
/**
******************************************************************************
* @addtogroup UAVObjects OpenPilot UAVObjects
* @{
* @addtogroup UAV Object Manager
* @brief The core UAV Objects functions, most of which are wrappered by
* autogenerated defines
* @{
*
*
* @file uavobjectmanager.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @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.
* @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"
// Constants
// Private types
/**
* List of event queues and the eventmask associated with the queue.
*/
struct ObjectEventListStruct {
xQueueHandle queue;
UAVObjEventCallback cb;
int32_t eventMask;
struct ObjectEventListStruct* next;
};
typedef struct ObjectEventListStruct ObjectEventList;
/**
* List of object instances, holds the actual data structure and instance ID
*/
struct ObjectInstListStruct {
void* data;
uint16_t instId;
struct ObjectInstListStruct* next;
};
typedef struct ObjectInstListStruct ObjectInstList;
/**
* List of objects registered in the object manager
*/
struct ObjectListStruct {
uint32_t id; /** The object ID */
const char* name; /** The object name */
int8_t isMetaobject; /** Set to 1 if this is a metaobject */
int8_t isSingleInstance; /** Set to 1 if this object has a single instance */
int8_t isSettings; /** Set to 1 if this object is a settings object */
uint16_t numBytes; /** Number of data bytes contained in the object (for a single instance) */
uint16_t numInstances; /** Number of instances */
struct ObjectListStruct* linkedObj; /** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */
ObjectInstList instances; /** List of object instances, instance 0 always exists */
ObjectEventList* events; /** Event queues registered on the object */
struct ObjectListStruct* next; /** Needed by linked list library (utlist.h) */
};
typedef struct ObjectListStruct ObjectList;
// Private functions
static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event);
static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId);
static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId);
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb, int32_t eventMask);
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb);
#if defined(PIOS_INCLUDE_SDCARD)
static void objectFilename(ObjectList* obj, uint8_t* filename);
static void customSPrintf(uint8_t* buffer, uint8_t* format, ...);
#endif
// Private variables
static ObjectList* objList;
static xSemaphoreHandle mutex;
static UAVObjMetadata defMetadata;
static UAVObjStats stats;
/**
* Initialize the object manager
* \return 0 Success
* \return -1 Failure
*/
int32_t UAVObjInitialize()
{
// Initialize variables
objList = NULL;
memset(&stats, 0, sizeof(UAVObjStats));
// Create mutex
mutex = xSemaphoreCreateRecursiveMutex();
if (mutex == NULL)
return -1;
// Initialize default metadata structure (metadata of metaobjects)
defMetadata.access = ACCESS_READWRITE;
defMetadata.gcsAccess = ACCESS_READWRITE;
defMetadata.telemetryAcked = 1;
defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.telemetryUpdatePeriod = 0;
defMetadata.gcsTelemetryAcked = 1;
defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.gcsTelemetryUpdatePeriod = 0;
defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.loggingUpdatePeriod = 0;
// Done
return 0;
}
/**
* Get the statistics counters
* @param[out] statsOut The statistics counters will be copied there
*/
void UAVObjGetStats(UAVObjStats* statsOut)
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
memcpy(statsOut, &stats, sizeof(UAVObjStats));
xSemaphoreGiveRecursive(mutex);
}
/**
* Clear the statistics counters
*/
void UAVObjClearStats()
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
memset(&stats, 0, sizeof(UAVObjStats));
xSemaphoreGiveRecursive(mutex);
}
/**
* Register and new object in the object manager.
* \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)
* \param[in] isSingleInstance Is this a single instance or multi-instance object
* \param[in] isSettings Is this a settings object
* \param[in] numBytes Number of bytes of object data (for one instance)
* \param[in] initCb Default field and metadata initialization function
* \return Object handle, or NULL if failure.
* \return
*/
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)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
ObjectList* metaObj;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Check that the object is not already registered
LL_FOREACH(objList, objEntry)
{
if (objEntry->id == id)
{
// Already registered, ignore
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Create and append entry
objEntry = (ObjectList*)pvPortMalloc(sizeof(ObjectList));
if (objEntry == NULL)
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
objEntry->id = id;
objEntry->name = name;
objEntry->isMetaobject = (int8_t)isMetaobject;
objEntry->isSingleInstance = (int8_t)isSingleInstance;
objEntry->isSettings = (int8_t)isSettings;
objEntry->numBytes = numBytes;
objEntry->events = NULL;
objEntry->numInstances = 0;
objEntry->instances.data = NULL;
objEntry->instances.instId = 0xFFFF;
objEntry->instances.next = NULL;
objEntry->linkedObj = NULL; // will be set later
LL_APPEND(objList, objEntry);
// Create instance zero
instEntry = createInstance(objEntry, 0);
if ( instEntry == NULL )
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Create metaobject and update linkedObj
if (isMetaobject)
{
objEntry->linkedObj = NULL; // will be set later
}
else
{
// Create metaobject
metaObj = (ObjectList*)UAVObjRegister(id+1, metaName, NULL, 1, 1, 0, sizeof(UAVObjMetadata), NULL);
// Link two objects
objEntry->linkedObj = metaObj;
metaObj->linkedObj = objEntry;
}
// Initialize object fields and metadata to default values
if ( initCb != NULL )
{
initCb((UAVObjHandle)objEntry, 0);
}
// Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object)
if ( !objEntry->isMetaobject )
{
UAVObjLoad( (UAVObjHandle)objEntry->linkedObj, 0 );
}
// If this is a settings object, attempt to load from SD card
if ( objEntry->isSettings )
{
UAVObjLoad( (UAVObjHandle)objEntry, 0 );
}
// Release lock
xSemaphoreGiveRecursive(mutex);
return (UAVObjHandle)objEntry;
}
/**
* Retrieve an object from the list given its id
* \param[in] The object ID
* \return The object or NULL if not found.
*/
UAVObjHandle UAVObjGetByID(uint32_t id)
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Look for object
LL_FOREACH(objList, objEntry)
{
if (objEntry->id == id)
{
// Release lock
xSemaphoreGiveRecursive(mutex);
// Done, object found
return (UAVObjHandle)objEntry;
}
}
// Object not found, release lock and return error
xSemaphoreGiveRecursive(mutex);
return NULL;
}
/**
* Retrieve an object from the list given its name
* \param[in] name The name of the object
* \return The object or NULL if not found.
*/
UAVObjHandle UAVObjGetByName(char* name)
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Look for object
LL_FOREACH(objList, objEntry)
{
if (objEntry->name != NULL && strcmp(objEntry->name, name) == 0)
{
// Release lock
xSemaphoreGiveRecursive(mutex);
// Done, object found
return (UAVObjHandle)objEntry;
}
}
// Object not found, release lock and return error
xSemaphoreGiveRecursive(mutex);
return NULL;
}
/**
* Get the object's ID
* \param[in] obj The object handle
* \return The object ID
*/
uint32_t UAVObjGetID(UAVObjHandle obj)
{
return ((ObjectList*)obj)->id;
}
/**
* Get the object's name
* \param[in] obj The object handle
* \return The object's name
*/
const char* UAVObjGetName(UAVObjHandle obj)
{
return ((ObjectList*)obj)->name;
}
/**
* Get the number of bytes of the object's data (for one instance)
* \param[in] obj The object handle
* \return The number of bytes
*/
uint32_t UAVObjGetNumBytes(UAVObjHandle obj)
{
return ((ObjectList*)obj)->numBytes;
}
/**
* 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.
* This function is normally only needed by the telemetry module.
* \param[in] obj The object handle
* \return The object linked object handle
*/
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj)
{
return (UAVObjHandle)(((ObjectList*)obj)->linkedObj);
}
/**
* Get the number of instances contained in the object.
* \param[in] obj The object handle
* \return The number of instances
*/
uint16_t UAVObjGetNumInstances(UAVObjHandle obj)
{
uint32_t numInstances;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
numInstances = ((ObjectList*)obj)->numInstances;
xSemaphoreGiveRecursive(mutex);
return numInstances;
}
/**
* Create a new instance in the object.
* \param[in] obj The object handle
* \return The instance ID or 0 if an error
*/
uint16_t UAVObjCreateInstance(UAVObjHandle obj, UAVObjInitializeCallback initCb)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Create new instance
objEntry = (ObjectList*)obj;
instEntry = createInstance(objEntry, objEntry->numInstances);
if ( instEntry == NULL )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Initialize instance data
if ( initCb != NULL )
{
initCb(obj, 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
*/
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
*/
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
*/
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
* \param[in] dataIn The byte array
* \return 0 if success or -1 if failure
*/
int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId, const uint8_t* dataIn)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast handle to object
objEntry = (ObjectList*)obj;
// Get the instance
instEntry = getInstance(objEntry, instId);
// If the instance does not exist create it and any other instances before it
if ( instEntry == NULL )
{
instEntry = createInstance(objEntry, instId);
if ( instEntry == NULL )
{
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
// Set the data
memcpy(instEntry->data, dataIn, objEntry->numBytes);
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Pack an object to a byte array
* \param[in] obj The object handle
* \param[in] instId The instance ID
* \param[out] dataOut The byte array
* \return 0 if success or -1 if failure
*/
int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t* dataOut)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast handle to object
objEntry = (ObjectList*)obj;
// Get the instance
instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL )
{
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Pack data
memcpy(dataOut, instEntry->data, objEntry->numBytes);
// Unlock
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.
* The object data can be restored using the UAVObjLoad function.
* @param[in] obj The object handle.
* @param[in] instId The instance ID
* @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)
{
#if defined(PIOS_INCLUDE_SDCARD)
uint32_t bytesWritten;
ObjectList* objEntry;
ObjectInstList* instEntry;
// Check for file system availability
if ( PIOS_SDCARD_IsMounted() == 0 )
{
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList*)obj;
// Get the instance information
instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Write the object ID
PIOS_FWRITE(file,&objEntry->id,sizeof(objEntry->id),&bytesWritten);
// Write the instance ID
if (!objEntry->isSingleInstance)
{
PIOS_FWRITE(file,&instEntry->instId,sizeof(instEntry->instId),&bytesWritten);
}
// Write the data and check that the write was successful
PIOS_FWRITE(file,instEntry->data,objEntry->numBytes,&bytesWritten);
if ( bytesWritten != objEntry->numBytes )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
struct fileHeader {
uint32_t id;
uint16_t instId;
uint16_t size;
} __attribute__((packed));
#define FLASH_MASK 0x001ff000 /* Select a sector */
/**
* Save the data of the specified object to the file system (SD card).
* If the object contains multiple instances, all of them will be saved.
* 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.
* @param[in] instId The instance ID
* @param[in] file File to append to
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList* objEntry = (ObjectList*)obj;
if(objEntry == NULL)
return -1;
ObjectInstList* instEntry = getInstance(objEntry, instId);
if(instEntry == NULL)
return -1;
if(instEntry->data == NULL)
return -1;
struct fileHeader header = {
.id = objEntry->id,
.instId = instId,
.size = objEntry->numBytes
};
uint32_t addr = (objEntry->id & FLASH_MASK);
PIOS_Flash_W25X_EraseSector(addr);
PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header));
PIOS_Flash_W25X_WriteData(addr + sizeof(header), instEntry->data,objEntry->numBytes);
#endif
#if defined(PIOS_INCLUDE_SDCARD)
FILEINFO file;
ObjectList* objEntry;
uint8_t filename[14];
// Check for file system availability
if ( PIOS_SDCARD_IsMounted() == 0 )
{
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList*)obj;
// Get filename
objectFilename(objEntry, filename);
// Open file
if ( PIOS_FOPEN_WRITE(filename,file) )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Append object
if ( UAVObjSaveToFile(obj, instId, &file) == -1 )
{
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done, close file and unlock
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* Load an object from the file system (SD card).
* @param[in] file File to read from
* @return The handle of the object loaded or NULL if a failure
*/
UAVObjHandle UAVObjLoadFromFile(FILEINFO* file)
{
#if defined(PIOS_INCLUDE_SDCARD)
uint32_t bytesRead;
ObjectList* objEntry;
ObjectInstList* instEntry;
uint32_t objId;
uint16_t instId;
UAVObjHandle obj;
// Check for file system availability
if ( PIOS_SDCARD_IsMounted() == 0 )
{
return NULL;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Read the object ID
if ( PIOS_FREAD(file,&objId,sizeof(objId),&bytesRead) )
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Get the object
obj = UAVObjGetByID(objId);
if ( obj == 0 )
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
objEntry = (ObjectList*)obj;
// Get the instance ID
instId = 0;
if ( !objEntry->isSingleInstance )
{
if ( PIOS_FREAD(file,&instId,sizeof(instId),&bytesRead) )
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Get the instance information
instEntry = getInstance(objEntry, instId);
// If the instance does not exist create it and any other instances before it
if ( instEntry == NULL )
{
instEntry = createInstance(objEntry, instId);
if ( instEntry == NULL )
{
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Read the instance data
if ( PIOS_FREAD(file,instEntry->data,objEntry->numBytes,&bytesRead) )
{
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return obj;
#else /* PIOS_INCLUDE_SDCARD */
return NULL;
#endif
}
/**
* Load an object from the file system (SD card).
* A file with the name of the object will be opened.
* 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
*/
int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList* objEntry = (ObjectList*)obj;
if(objEntry == NULL)
return -1;
ObjectInstList* instEntry = getInstance(objEntry, instId);
if(instEntry == NULL)
return -1;
if(instEntry->data == NULL)
return -1;
struct fileHeader header;
uint32_t addr = (objEntry->id & FLASH_MASK);
PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header));
if(header.id != objEntry->id)
return -1;
// Read the instance data
if (PIOS_Flash_W25X_ReadData(addr + sizeof(header) ,instEntry->data, objEntry->numBytes) != 0)
return -1;
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED);
#endif
#if defined(PIOS_INCLUDE_SDCARD)
FILEINFO file;
ObjectList* objEntry;
UAVObjHandle loadedObj;
ObjectList* loadedObjEntry;
uint8_t filename[14];
// Check for file system availability
if ( PIOS_SDCARD_IsMounted() == 0 )
{
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList*)obj;
// Get filename
objectFilename(objEntry, filename);
// Open file
if ( PIOS_FOPEN_READ(filename,file) )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Load object
loadedObj = UAVObjLoadFromFile(&file);
if (loadedObj == 0)
{
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Check that the IDs match
loadedObjEntry = (ObjectList*)loadedObj;
if ( loadedObjEntry->id != objEntry->id )
{
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done, close file and unlock
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* 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
*/
int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList* objEntry = (ObjectList*)obj;
if(objEntry == NULL)
return -1;
uint32_t addr = (objEntry->id & FLASH_MASK);
PIOS_Flash_W25X_EraseSector(addr);
#endif
#if defined(PIOS_INCLUDE_SDCARD)
ObjectList* objEntry;
uint8_t filename[14];
// Check for file system availability
if ( PIOS_SDCARD_IsMounted() == 0 )
{
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList*)obj;
// Get filename
objectFilename(objEntry, filename);
// Delete file
PIOS_FUNLINK(filename);
// Done
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* Save all settings objects to the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSaveSettings()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isSettings )
{
// Save object
if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Load all settings objects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjLoadSettings()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isSettings )
{
// Load object
if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Delete all settings objects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjDeleteSettings()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isSettings )
{
// Save object
if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Save all metaobjects to the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSaveMetaobjects()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isMetaobject )
{
// Save object
if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Load all metaobjects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjLoadMetaobjects()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isMetaobject )
{
// Load object
if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Delete all metaobjects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjDeleteMetaobjects()
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry)
{
// Check if this is a settings object
if ( objEntry->isMetaobject )
{
// Load object
if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Set the object data
* \param[in] obj The object handle
* \param[in] dataIn The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetData(UAVObjHandle obj, const void* dataIn)
{
return UAVObjSetInstanceData(obj, 0, dataIn);
}
/**
* 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
*/
int32_t UAVObjGetData(UAVObjHandle obj, void* dataOut)
{
return UAVObjGetInstanceData(obj, 0, dataOut);
}
/**
* Set the data of a specific object instance
* \param[in] obj The object handle
* \param[in] instId The object instance ID
* \param[in] dataIn The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, const void* dataIn)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
UAVObjMetadata* mdata;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object info
objEntry = (ObjectList*)obj;
// Check access level
if ( !objEntry->isMetaobject )
{
mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data);
if ( mdata->access == ACCESS_READONLY )
{
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
// Get instance information
instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL )
{
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Set data
memcpy(instEntry->data, dataIn, objEntry->numBytes);
// Fire event
sendEvent(objEntry, instId, EV_UPDATED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Get the data of a specific object instance
* \param[in] obj The object handle
* \param[in] instId The object instance ID
* \param[out] dataOut The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, void* dataOut)
{
ObjectList* objEntry;
ObjectInstList* instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object info
objEntry = (ObjectList*)obj;
// Get instance information
instEntry = getInstance(objEntry, instId);
if ( instEntry == NULL )
{
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Set data
memcpy(dataOut, instEntry->data, objEntry->numBytes);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Set the object metadata
* \param[in] obj The object handle
* \param[in] dataIn The object's metadata structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata* dataIn)
{
ObjectList* objEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Set metadata (metadata of metaobjects can not be modified)
objEntry = (ObjectList*)obj;
if (!objEntry->isMetaobject)
{
UAVObjSetData((UAVObjHandle)objEntry->linkedObj, dataIn);
}
else
{
return -1;
}
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Get the object metadata
* \param[in] obj The object handle
* \param[out] dataOut The object's metadata structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata* dataOut)
{
ObjectList* objEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Get metadata
objEntry = (ObjectList*)obj;
if (objEntry->isMetaobject)
{
memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata));
}
else
{
UAVObjGetData((UAVObjHandle)objEntry->linkedObj, dataOut);
}
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Check if an object is read only
* \param[in] obj The object handle
* \return
* \arg 0 if not read only
* \arg 1 if read only
* \arg -1 if unable to get meta data
*/
int8_t UAVObjReadOnly(UAVObjHandle obj)
{
ObjectList* objEntry;
UAVObjMetadata* mdata;
// Cast to object info
objEntry = (ObjectList*)obj;
// Check access level
if ( !objEntry->isMetaobject )
{
mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data);
return mdata->access == ACCESS_READONLY;
}
return -1;
}
/**
* Connect an event queue to the object, if the queue is already connected then the event mask is only updated.
* All events matching the event mask will be pushed to the event queue.
* \param[in] obj The object handle
* \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
*/
int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, int32_t eventMask)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = connectObj(obj, queue, 0, eventMask);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* Disconnect an event queue from the object.
* \param[in] obj The object handle
* \param[in] queue The event queue
* \return 0 if success or -1 if failure
*/
int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, queue, 0);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* 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.
* \param[in] obj The object handle
* \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
*/
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, int32_t eventMask)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = connectObj(obj, 0, cb, eventMask);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* Disconnect an event callback from the object.
* \param[in] obj The object handle
* \param[in] cb The event callback
* \return 0 if success or -1 if failure
*/
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, 0, cb);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* 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.
* \param[in] obj The object handle
*/
void UAVObjRequestUpdate(UAVObjHandle obj)
{
UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES);
}
/**
* 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.
* \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);
sendEvent((ObjectList*)obj, instId, EV_UPDATE_REQ);
xSemaphoreGiveRecursive(mutex);
}
/**
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
* \param[in] obj The object handle
*/
void UAVObjUpdated(UAVObjHandle obj)
{
UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES);
}
/**
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
* \param[in] obj The object handle
* \param[in] instId The object instance ID
*/
void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId)
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
sendEvent((ObjectList*)obj, instId, EV_UPDATED_MANUAL);
xSemaphoreGiveRecursive(mutex);
}
/**
* Iterate through all objects in the list.
* \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))
{
ObjectList* objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Iterate through the list and invoke iterator for each object
LL_FOREACH(objList, objEntry)
{
(*iterator)((UAVObjHandle)objEntry);
}
// Release lock
xSemaphoreGiveRecursive(mutex);
}
/**
* Send an event to all event queues registered on the object.
*/
static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event)
{
ObjectEventList* eventEntry;
UAVObjEvent msg;
// Setup event
msg.obj = (UAVObjHandle)obj;
msg.event = event;
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)
{
if ( eventEntry->eventMask == 0 || (eventEntry->eventMask & event) != 0 )
{
// Send to queue if a valid queue is registered
if (eventEntry->queue != 0)
{
if ( xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE ) // will not block
{
++stats.eventErrors;
}
}
// 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
{
++stats.eventErrors;
}
}
}
}
// Done
return 0;
}
/**
* Create a new object instance, return the instance info or NULL if failure.
*/
static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId)
{
ObjectInstList* instEntry;
int32_t n;
// For single instance objects, only instance zero is allowed
if (obj->isSingleInstance && instId != 0)
{
return NULL;
}
// Make sure that the instance ID is within limits
if (instId >= UAVOBJ_MAX_INSTANCES)
{
return NULL;
}
// Check if the instance already exists
if ( getInstance(obj, instId) != NULL )
{
return NULL;
}
// Create any missing instances (all instance IDs must be sequential)
for (n = obj->numInstances; n < instId; ++n)
{
if ( createInstance(obj, n) == NULL )
{
return NULL;
}
}
if(instId == 0) /* Instance 0 ObjectInstList allocated with ObjectList element */
{
instEntry = &obj->instances;
instEntry->data = pvPortMalloc(obj->numBytes);
if (instEntry->data == NULL) return NULL;
memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId;
} else
{
// Create the actual instance
instEntry = (ObjectInstList*)pvPortMalloc(sizeof(ObjectInstList));
if (instEntry == NULL) return NULL;
instEntry->data = pvPortMalloc(obj->numBytes);
if (instEntry->data == NULL) return NULL;
memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId;
LL_APPEND(obj->instances.next, instEntry);
}
++obj->numInstances;
// Fire event
UAVObjInstanceUpdated((UAVObjHandle)obj, instId);
// Done
return instEntry;
}
/**
* Get the instance information or NULL if the instance does not exist
*/
static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId)
{
ObjectInstList* instEntry;
// Look for specified instance ID
LL_FOREACH(&(obj->instances), instEntry)
{
if (instEntry->instId == instId)
{
return instEntry;
}
}
// 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 */
/**
******************************************************************************
* @addtogroup UAVObjects OpenPilot UAVObjects
* @{
* @addtogroup UAV Object Manager
* @brief The core UAV Objects functions, most of which are wrappered by
* autogenerated defines
* @{
*
*
* @file uavobjectmanager.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @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.
* @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"
// Constants
// Private types
/**
* List of event queues and the eventmask associated with the queue.
*/
struct ObjectEventListStruct {
xQueueHandle queue;
UAVObjEventCallback cb;
int32_t eventMask;
struct ObjectEventListStruct *next;
};
typedef struct ObjectEventListStruct ObjectEventList;
/**
* List of object instances, holds the actual data structure and instance ID
*/
struct ObjectInstListStruct {
void *data;
uint16_t instId;
struct ObjectInstListStruct *next;
};
typedef struct ObjectInstListStruct ObjectInstList;
/**
* List of objects registered in the object manager
*/
struct ObjectListStruct {
uint32_t id;
/** The object ID */
const char *name;
/** The object name */
int8_t isMetaobject;
/** Set to 1 if this is a metaobject */
int8_t isSingleInstance;
/** Set to 1 if this object has a single instance */
int8_t isSettings;
/** Set to 1 if this object is a settings object */
uint16_t numBytes;
/** Number of data bytes contained in the object (for a single instance) */
uint16_t numInstances;
/** Number of instances */
struct ObjectListStruct *linkedObj;
/** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */
ObjectInstList instances;
/** List of object instances, instance 0 always exists */
ObjectEventList *events;
/** Event queues registered on the object */
struct ObjectListStruct *next;
/** Needed by linked list library (utlist.h) */
};
typedef struct ObjectListStruct ObjectList;
// Private functions
static int32_t sendEvent(ObjectList * obj, uint16_t instId,
UAVObjEventType event);
static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId);
static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId);
static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue,
UAVObjEventCallback cb, int32_t eventMask);
static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue,
UAVObjEventCallback cb);
#if defined(PIOS_INCLUDE_SDCARD)
static void objectFilename(ObjectList * obj, uint8_t * filename);
static void customSPrintf(uint8_t * buffer, uint8_t * format, ...);
#endif
// Private variables
static ObjectList *objList;
static xSemaphoreHandle mutex;
static UAVObjMetadata defMetadata;
static UAVObjStats stats;
/**
* Initialize the object manager
* \return 0 Success
* \return -1 Failure
*/
int32_t UAVObjInitialize()
{
// Initialize variables
objList = NULL;
memset(&stats, 0, sizeof(UAVObjStats));
// Create mutex
mutex = xSemaphoreCreateRecursiveMutex();
if (mutex == NULL)
return -1;
// Initialize default metadata structure (metadata of metaobjects)
defMetadata.access = ACCESS_READWRITE;
defMetadata.gcsAccess = ACCESS_READWRITE;
defMetadata.telemetryAcked = 1;
defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.telemetryUpdatePeriod = 0;
defMetadata.gcsTelemetryAcked = 1;
defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.gcsTelemetryUpdatePeriod = 0;
defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE;
defMetadata.loggingUpdatePeriod = 0;
// Done
return 0;
}
/**
* Get the statistics counters
* @param[out] statsOut The statistics counters will be copied there
*/
void UAVObjGetStats(UAVObjStats * statsOut)
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
memcpy(statsOut, &stats, sizeof(UAVObjStats));
xSemaphoreGiveRecursive(mutex);
}
/**
* Clear the statistics counters
*/
void UAVObjClearStats()
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
memset(&stats, 0, sizeof(UAVObjStats));
xSemaphoreGiveRecursive(mutex);
}
/**
* Register and new object in the object manager.
* \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)
* \param[in] isSingleInstance Is this a single instance or multi-instance object
* \param[in] isSettings Is this a settings object
* \param[in] numBytes Number of bytes of object data (for one instance)
* \param[in] initCb Default field and metadata initialization function
* \return Object handle, or NULL if failure.
* \return
*/
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)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
ObjectList *metaObj;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Check that the object is not already registered
LL_FOREACH(objList, objEntry) {
if (objEntry->id == id) {
// Already registered, ignore
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Create and append entry
objEntry = (ObjectList *) pvPortMalloc(sizeof(ObjectList));
if (objEntry == NULL) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
objEntry->id = id;
objEntry->name = name;
objEntry->isMetaobject = (int8_t) isMetaobject;
objEntry->isSingleInstance = (int8_t) isSingleInstance;
objEntry->isSettings = (int8_t) isSettings;
objEntry->numBytes = numBytes;
objEntry->events = NULL;
objEntry->numInstances = 0;
objEntry->instances.data = NULL;
objEntry->instances.instId = 0xFFFF;
objEntry->instances.next = NULL;
objEntry->linkedObj = NULL; // will be set later
LL_APPEND(objList, objEntry);
// Create instance zero
instEntry = createInstance(objEntry, 0);
if (instEntry == NULL) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Create metaobject and update linkedObj
if (isMetaobject) {
objEntry->linkedObj = NULL; // will be set later
} else {
// Create metaobject
metaObj =
(ObjectList *) UAVObjRegister(id + 1, metaName,
NULL, 1, 1, 0,
sizeof
(UAVObjMetadata),
NULL);
// Link two objects
objEntry->linkedObj = metaObj;
metaObj->linkedObj = objEntry;
}
// Initialize object fields and metadata to default values
if (initCb != NULL) {
initCb((UAVObjHandle) objEntry, 0);
}
// Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object)
if (!objEntry->isMetaobject) {
UAVObjLoad((UAVObjHandle) objEntry->linkedObj, 0);
}
// If this is a settings object, attempt to load from SD card
if (objEntry->isSettings) {
UAVObjLoad((UAVObjHandle) objEntry, 0);
}
// Release lock
xSemaphoreGiveRecursive(mutex);
return (UAVObjHandle) objEntry;
}
/**
* Retrieve an object from the list given its id
* \param[in] The object ID
* \return The object or NULL if not found.
*/
UAVObjHandle UAVObjGetByID(uint32_t id)
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Look for object
LL_FOREACH(objList, objEntry) {
if (objEntry->id == id) {
// Release lock
xSemaphoreGiveRecursive(mutex);
// Done, object found
return (UAVObjHandle) objEntry;
}
}
// Object not found, release lock and return error
xSemaphoreGiveRecursive(mutex);
return NULL;
}
/**
* Retrieve an object from the list given its name
* \param[in] name The name of the object
* \return The object or NULL if not found.
*/
UAVObjHandle UAVObjGetByName(char *name)
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Look for object
LL_FOREACH(objList, objEntry) {
if (objEntry->name != NULL
&& strcmp(objEntry->name, name) == 0) {
// Release lock
xSemaphoreGiveRecursive(mutex);
// Done, object found
return (UAVObjHandle) objEntry;
}
}
// Object not found, release lock and return error
xSemaphoreGiveRecursive(mutex);
return NULL;
}
/**
* Get the object's ID
* \param[in] obj The object handle
* \return The object ID
*/
uint32_t UAVObjGetID(UAVObjHandle obj)
{
return ((ObjectList *) obj)->id;
}
/**
* Get the object's name
* \param[in] obj The object handle
* \return The object's name
*/
const char *UAVObjGetName(UAVObjHandle obj)
{
return ((ObjectList *) obj)->name;
}
/**
* Get the number of bytes of the object's data (for one instance)
* \param[in] obj The object handle
* \return The number of bytes
*/
uint32_t UAVObjGetNumBytes(UAVObjHandle obj)
{
return ((ObjectList *) obj)->numBytes;
}
/**
* 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.
* This function is normally only needed by the telemetry module.
* \param[in] obj The object handle
* \return The object linked object handle
*/
UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj)
{
return (UAVObjHandle) (((ObjectList *) obj)->linkedObj);
}
/**
* Get the number of instances contained in the object.
* \param[in] obj The object handle
* \return The number of instances
*/
uint16_t UAVObjGetNumInstances(UAVObjHandle obj)
{
uint32_t numInstances;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
numInstances = ((ObjectList *) obj)->numInstances;
xSemaphoreGiveRecursive(mutex);
return numInstances;
}
/**
* Create a new instance in the object.
* \param[in] obj The object handle
* \return The instance ID or 0 if an error
*/
uint16_t UAVObjCreateInstance(UAVObjHandle obj,
UAVObjInitializeCallback initCb)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Create new instance
objEntry = (ObjectList *) obj;
instEntry = createInstance(objEntry, objEntry->numInstances);
if (instEntry == NULL) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Initialize instance data
if (initCb != NULL) {
initCb(obj, 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
*/
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
*/
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
*/
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
* \param[in] dataIn The byte array
* \return 0 if success or -1 if failure
*/
int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId,
const uint8_t * dataIn)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast handle to object
objEntry = (ObjectList *) obj;
// Get the instance
instEntry = getInstance(objEntry, instId);
// If the instance does not exist create it and any other instances before it
if (instEntry == NULL) {
instEntry = createInstance(objEntry, instId);
if (instEntry == NULL) {
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
// Set the data
memcpy(instEntry->data, dataIn, objEntry->numBytes);
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Pack an object to a byte array
* \param[in] obj The object handle
* \param[in] instId The instance ID
* \param[out] dataOut The byte array
* \return 0 if success or -1 if failure
*/
int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t * dataOut)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast handle to object
objEntry = (ObjectList *) obj;
// Get the instance
instEntry = getInstance(objEntry, instId);
if (instEntry == NULL) {
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Pack data
memcpy(dataOut, instEntry->data, objEntry->numBytes);
// Unlock
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.
* The object data can be restored using the UAVObjLoad function.
* @param[in] obj The object handle.
* @param[in] instId The instance ID
* @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)
{
#if defined(PIOS_INCLUDE_SDCARD)
uint32_t bytesWritten;
ObjectList *objEntry;
ObjectInstList *instEntry;
// Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList *) obj;
// Get the instance information
instEntry = getInstance(objEntry, instId);
if (instEntry == NULL) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Write the object ID
PIOS_FWRITE(file, &objEntry->id, sizeof(objEntry->id),
&bytesWritten);
// Write the instance ID
if (!objEntry->isSingleInstance) {
PIOS_FWRITE(file, &instEntry->instId,
sizeof(instEntry->instId), &bytesWritten);
}
// Write the data and check that the write was successful
PIOS_FWRITE(file, instEntry->data, objEntry->numBytes,
&bytesWritten);
if (bytesWritten != objEntry->numBytes) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* Save the data of the specified object to the file system (SD card).
* If the object contains multiple instances, all of them will be saved.
* 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.
* @param[in] instId The instance ID
* @param[in] file File to append to
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList *objEntry = (ObjectList *) obj;
if (objEntry == NULL)
return -1;
ObjectInstList *instEntry = getInstance(objEntry, instId);
if (instEntry == NULL)
return -1;
if (instEntry->data == NULL)
return -1;
if (PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0)
return -1;
#endif
#if defined(PIOS_INCLUDE_SDCARD)
FILEINFO file;
ObjectList *objEntry;
uint8_t filename[14];
// Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList *) obj;
// Get filename
objectFilename(objEntry, filename);
// Open file
if (PIOS_FOPEN_WRITE(filename, file)) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Append object
if (UAVObjSaveToFile(obj, instId, &file) == -1) {
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done, close file and unlock
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* Load an object from the file system (SD card).
* @param[in] file File to read from
* @return The handle of the object loaded or NULL if a failure
*/
UAVObjHandle UAVObjLoadFromFile(FILEINFO * file)
{
#if defined(PIOS_INCLUDE_SDCARD)
uint32_t bytesRead;
ObjectList *objEntry;
ObjectInstList *instEntry;
uint32_t objId;
uint16_t instId;
UAVObjHandle obj;
// Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
return NULL;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Read the object ID
if (PIOS_FREAD(file, &objId, sizeof(objId), &bytesRead)) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Get the object
obj = UAVObjGetByID(objId);
if (obj == 0) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
objEntry = (ObjectList *) obj;
// Get the instance ID
instId = 0;
if (!objEntry->isSingleInstance) {
if (PIOS_FREAD
(file, &instId, sizeof(instId), &bytesRead)) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Get the instance information
instEntry = getInstance(objEntry, instId);
// If the instance does not exist create it and any other instances before it
if (instEntry == NULL) {
instEntry = createInstance(objEntry, instId);
if (instEntry == NULL) {
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return NULL;
}
}
// Read the instance data
if (PIOS_FREAD
(file, instEntry->data, objEntry->numBytes, &bytesRead)) {
xSemaphoreGiveRecursive(mutex);
return NULL;
}
// Fire event
sendEvent(objEntry, instId, EV_UNPACKED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return obj;
#else /* PIOS_INCLUDE_SDCARD */
return NULL;
#endif
}
/**
* Load an object from the file system (SD card).
* A file with the name of the object will be opened.
* 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
*/
int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
ObjectList *objEntry = (ObjectList *) obj;
if (objEntry == NULL)
return -1;
ObjectInstList *instEntry = getInstance(objEntry, instId);
if (instEntry == NULL)
return -1;
if (instEntry->data == NULL)
return -1;
// Fire event on success
if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0)
sendEvent(objEntry, instId, EV_UNPACKED);
else
return -1;
#endif
#if defined(PIOS_INCLUDE_SDCARD)
FILEINFO file;
ObjectList *objEntry;
UAVObjHandle loadedObj;
ObjectList *loadedObjEntry;
uint8_t filename[14];
// Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList *) obj;
// Get filename
objectFilename(objEntry, filename);
// Open file
if (PIOS_FOPEN_READ(filename, file)) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Load object
loadedObj = UAVObjLoadFromFile(&file);
if (loadedObj == 0) {
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Check that the IDs match
loadedObjEntry = (ObjectList *) loadedObj;
if (loadedObjEntry->id != objEntry->id) {
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Done, close file and unlock
PIOS_FCLOSE(file);
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* 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
*/
int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId)
{
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
PIOS_FLASHFS_ObjDelete(obj, instId);
#endif
#if defined(PIOS_INCLUDE_SDCARD)
ObjectList *objEntry;
uint8_t filename[14];
// Check for file system availability
if (PIOS_SDCARD_IsMounted() == 0) {
return -1;
}
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object
objEntry = (ObjectList *) obj;
// Get filename
objectFilename(objEntry, filename);
// Delete file
PIOS_FUNLINK(filename);
// Done
xSemaphoreGiveRecursive(mutex);
#endif /* PIOS_INCLUDE_SDCARD */
return 0;
}
/**
* Save all settings objects to the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSaveSettings()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isSettings) {
// Save object
if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
-1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Load all settings objects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjLoadSettings()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isSettings) {
// Load object
if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
-1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Delete all settings objects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjDeleteSettings()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isSettings) {
// Save object
if (UAVObjDelete((UAVObjHandle) objEntry, 0)
== -1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Save all metaobjects to the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjSaveMetaobjects()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Save all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isMetaobject) {
// Save object
if (UAVObjSave((UAVObjHandle) objEntry, 0) ==
-1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Load all metaobjects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjLoadMetaobjects()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isMetaobject) {
// Load object
if (UAVObjLoad((UAVObjHandle) objEntry, 0) ==
-1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Delete all metaobjects from the SD card.
* @return 0 if success or -1 if failure
*/
int32_t UAVObjDeleteMetaobjects()
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Load all settings objects
LL_FOREACH(objList, objEntry) {
// Check if this is a settings object
if (objEntry->isMetaobject) {
// Load object
if (UAVObjDelete((UAVObjHandle) objEntry, 0)
== -1) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
}
// Done
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Set the object data
* \param[in] obj The object handle
* \param[in] dataIn The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetData(UAVObjHandle obj, const void *dataIn)
{
return UAVObjSetInstanceData(obj, 0, dataIn);
}
/**
* 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
*/
int32_t UAVObjGetData(UAVObjHandle obj, void *dataOut)
{
return UAVObjGetInstanceData(obj, 0, dataOut);
}
/**
* Set the data of a specific object instance
* \param[in] obj The object handle
* \param[in] instId The object instance ID
* \param[in] dataIn The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId,
const void *dataIn)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
UAVObjMetadata *mdata;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object info
objEntry = (ObjectList *) obj;
// Check access level
if (!objEntry->isMetaobject) {
mdata =
(UAVObjMetadata *) (objEntry->linkedObj->instances.
data);
if (mdata->access == ACCESS_READONLY) {
xSemaphoreGiveRecursive(mutex);
return -1;
}
}
// Get instance information
instEntry = getInstance(objEntry, instId);
if (instEntry == NULL) {
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Set data
memcpy(instEntry->data, dataIn, objEntry->numBytes);
// Fire event
sendEvent(objEntry, instId, EV_UPDATED);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Get the data of a specific object instance
* \param[in] obj The object handle
* \param[in] instId The object instance ID
* \param[out] dataOut The object's data structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId,
void *dataOut)
{
ObjectList *objEntry;
ObjectInstList *instEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Cast to object info
objEntry = (ObjectList *) obj;
// Get instance information
instEntry = getInstance(objEntry, instId);
if (instEntry == NULL) {
// Error, unlock and return
xSemaphoreGiveRecursive(mutex);
return -1;
}
// Set data
memcpy(dataOut, instEntry->data, objEntry->numBytes);
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Set the object metadata
* \param[in] obj The object handle
* \param[in] dataIn The object's metadata structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn)
{
ObjectList *objEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Set metadata (metadata of metaobjects can not be modified)
objEntry = (ObjectList *) obj;
if (!objEntry->isMetaobject) {
UAVObjSetData((UAVObjHandle) objEntry->linkedObj,
dataIn);
} else {
return -1;
}
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Get the object metadata
* \param[in] obj The object handle
* \param[out] dataOut The object's metadata structure
* \return 0 if success or -1 if failure
*/
int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut)
{
ObjectList *objEntry;
// Lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Get metadata
objEntry = (ObjectList *) obj;
if (objEntry->isMetaobject) {
memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata));
} else {
UAVObjGetData((UAVObjHandle) objEntry->linkedObj,
dataOut);
}
// Unlock
xSemaphoreGiveRecursive(mutex);
return 0;
}
/**
* Check if an object is read only
* \param[in] obj The object handle
* \return
* \arg 0 if not read only
* \arg 1 if read only
* \arg -1 if unable to get meta data
*/
int8_t UAVObjReadOnly(UAVObjHandle obj)
{
ObjectList *objEntry;
UAVObjMetadata *mdata;
// Cast to object info
objEntry = (ObjectList *) obj;
// Check access level
if (!objEntry->isMetaobject) {
mdata =
(UAVObjMetadata *) (objEntry->linkedObj->instances.
data);
return mdata->access == ACCESS_READONLY;
}
return -1;
}
/**
* Connect an event queue to the object, if the queue is already connected then the event mask is only updated.
* All events matching the event mask will be pushed to the event queue.
* \param[in] obj The object handle
* \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
*/
int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue,
int32_t eventMask)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = connectObj(obj, queue, 0, eventMask);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* Disconnect an event queue from the object.
* \param[in] obj The object handle
* \param[in] queue The event queue
* \return 0 if success or -1 if failure
*/
int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, queue, 0);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* 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.
* \param[in] obj The object handle
* \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
*/
int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb,
int32_t eventMask)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = connectObj(obj, 0, cb, eventMask);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* Disconnect an event callback from the object.
* \param[in] obj The object handle
* \param[in] cb The event callback
* \return 0 if success or -1 if failure
*/
int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb)
{
int32_t res;
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
res = disconnectObj(obj, 0, cb);
xSemaphoreGiveRecursive(mutex);
return res;
}
/**
* 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.
* \param[in] obj The object handle
*/
void UAVObjRequestUpdate(UAVObjHandle obj)
{
UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES);
}
/**
* 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.
* \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);
sendEvent((ObjectList *) obj, instId, EV_UPDATE_REQ);
xSemaphoreGiveRecursive(mutex);
}
/**
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
* \param[in] obj The object handle
*/
void UAVObjUpdated(UAVObjHandle obj)
{
UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES);
}
/**
* Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object).
* \param[in] obj The object handle
* \param[in] instId The object instance ID
*/
void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId)
{
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
sendEvent((ObjectList *) obj, instId, EV_UPDATED_MANUAL);
xSemaphoreGiveRecursive(mutex);
}
/**
* Iterate through all objects in the list.
* \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))
{
ObjectList *objEntry;
// Get lock
xSemaphoreTakeRecursive(mutex, portMAX_DELAY);
// Iterate through the list and invoke iterator for each object
LL_FOREACH(objList, objEntry) {
(*iterator) ((UAVObjHandle) objEntry);
}
// Release lock
xSemaphoreGiveRecursive(mutex);
}
/**
* Send an event to all event queues registered on the object.
*/
static int32_t sendEvent(ObjectList * obj, uint16_t instId,
UAVObjEventType event)
{
ObjectEventList *eventEntry;
UAVObjEvent msg;
// Setup event
msg.obj = (UAVObjHandle) obj;
msg.event = event;
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) {
if (eventEntry->eventMask == 0
|| (eventEntry->eventMask & event) != 0) {
// Send to queue if a valid queue is registered
if (eventEntry->queue != 0) {
if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block
{
++stats.eventErrors;
}
}
// 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
{
++stats.eventErrors;
}
}
}
}
// Done
return 0;
}
/**
* Create a new object instance, return the instance info or NULL if failure.
*/
static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId)
{
ObjectInstList *instEntry;
int32_t n;
// For single instance objects, only instance zero is allowed
if (obj->isSingleInstance && instId != 0) {
return NULL;
}
// Make sure that the instance ID is within limits
if (instId >= UAVOBJ_MAX_INSTANCES) {
return NULL;
}
// Check if the instance already exists
if (getInstance(obj, instId) != NULL) {
return NULL;
}
// Create any missing instances (all instance IDs must be sequential)
for (n = obj->numInstances; n < instId; ++n) {
if (createInstance(obj, n) == NULL) {
return NULL;
}
}
if (instId == 0) { /* Instance 0 ObjectInstList allocated with ObjectList element */
instEntry = &obj->instances;
instEntry->data = pvPortMalloc(obj->numBytes);
if (instEntry->data == NULL)
return NULL;
memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId;
} else {
// Create the actual instance
instEntry =
(ObjectInstList *)
pvPortMalloc(sizeof(ObjectInstList));
if (instEntry == NULL)
return NULL;
instEntry->data = pvPortMalloc(obj->numBytes);
if (instEntry->data == NULL)
return NULL;
memset(instEntry->data, 0, obj->numBytes);
instEntry->instId = instId;
LL_APPEND(obj->instances.next, instEntry);
}
++obj->numInstances;
// Fire event
UAVObjInstanceUpdated((UAVObjHandle) obj, instId);
// Done
return instEntry;
}
/**
* Get the instance information or NULL if the instance does not exist
*/
static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId)
{
ObjectInstList *instEntry;
// Look for specified instance ID
LL_FOREACH(&(obj->instances), instEntry) {
if (instEntry->instId == instId) {
return instEntry;
}
}
// 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
amps
aquired
armed
autonomous flight
battery
camera
@ -32,8 +33,10 @@ complete
connected
connection
control
coptercontrol
critical
disabled
disarmed
disconnected
feet
figure eight
@ -58,11 +61,13 @@ lost
low altitude
low battery
low gps quality
magic
manual flight
maxium
meters
minimum
mode
moved
MPH
navigation
OpenPilot
@ -122,8 +127,4 @@ hundread
thousand
Upto: OpenPilot
critical
battery
point

View File

@ -1,5 +1,5 @@
[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]
NumberOfWorkspaces=6
@ -7,7 +7,7 @@ Workspace1=Flight data
Icon1=:/core/images/ah.png
Workspace2=Configuration
Icon2=:/core/images/config.png
Workspace3=Large Map
Workspace3=Flight Planner
Icon3=:/core/images/world.png
Workspace4=Scopes
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\side0\type=uavGadget
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\splitterOrientation=2
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\classId=LineardialGadget
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\showToolbars=false
Mode3\splitter\type=splitter
@ -194,6 +203,7 @@ Mode3\splitter\side1\splitterOrientation=2
Mode3\splitter\side1\splitterSizes=395, 236
Mode3\splitter\side1\side0\type=uavGadget
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\splitterOrientation=1
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\classId=ScopeGadget
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]
size=0
[%General]
OverrideLanguage=en_AU
SaveSettingsOnExit=true
TerminalEmulator=xterm -e
LastPreferenceCategory=LineardialGadget
LastPreferencePage=Roll Desired 1
SettingsWindowWidth=921
SettingsWindowHeight=534
[UAVGadgetConfigurations]
configInfo\version=1.2.0
@ -1233,6 +1235,40 @@ LineardialGadget\Mainboard%20CPU\data\factor=1
LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false
LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0
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\sourceDataObject=AttitudeActual
LineardialGadget\PitchActual\data\sourceObjectField=Pitch
@ -1267,6 +1303,23 @@ LineardialGadget\Roll\data\factor=1
LineardialGadget\Roll\data\useOpenGLFlag=false
LineardialGadget\Roll\configInfo\version=0.0.0
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\sourceDataObject=GCSTelemetryStats
LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate
@ -1335,6 +1388,23 @@ LineardialGadget\Yaw\data\factor=1
LineardialGadget\Yaw\data\useOpenGLFlag=false
LineardialGadget\Yaw\configInfo\version=0.0.0
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\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
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\useMemoryCache=true
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\configInfo\version=0.0.0
OPMapGadget\Google%20Sat\configInfo\locked=false
@ -1875,52 +1911,18 @@ Uploader\default\data\defaultStopBits=0
Uploader\default\data\defaultPort=/dev/ttyS0
Uploader\default\configInfo\version=0.0.0
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]
SoundNotifyPlugin\data\Current\1\SoundCollectionPath=%%DATAPATH%%sounds
SoundNotifyPlugin\data\Current\1\CurrentLanguage=default
SoundNotifyPlugin\data\Current\1\ObjectField=Channel
SoundNotifyPlugin\data\Current\1\DataObject=ActuatorCommand
SoundNotifyPlugin\data\Current\1\Value=Equal to
SoundNotifyPlugin\data\Current\1\SoundCollectionPath=
SoundNotifyPlugin\data\Current\1\CurrentLanguage=
SoundNotifyPlugin\data\Current\1\ObjectField=
SoundNotifyPlugin\data\Current\1\DataObject=
SoundNotifyPlugin\data\Current\1\Value=
SoundNotifyPlugin\data\Current\1\ValueSpinBox=0
SoundNotifyPlugin\data\Current\1\Sound1=
SoundNotifyPlugin\data\Current\1\Sound2=
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\ExpireTimeout=0
SoundNotifyPlugin\data\Current\size=1
@ -1928,9 +1930,3 @@ SoundNotifyPlugin\data\listNotifies\size=0
SoundNotifyPlugin\data\EnableSound=false
SoundNotifyPlugin\configInfo\version=1.0.0
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
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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 "opmapgadgetconfiguration.h"
#include "utils/pathutils.h"
#include <QDir>
OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) :
IUAVGadgetConfiguration(classId, parent),
m_mapProvider("GoogleHybrid"),
m_defaultZoom(2),
m_defaultLatitude(0),
m_defaultLongitude(0),
m_useOpenGL(false),
m_showTileGridLines(false),
m_accessMode("ServerAndCache"),
m_useMemoryCache(true),
m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()),
m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png"))
{
//if a saved configuration exists load it
if(qSettings != 0) {
QString mapProvider = qSettings->value("mapProvider").toString();
int zoom = qSettings->value("defaultZoom").toInt();
double latitude= qSettings->value("defaultLatitude").toDouble();
double longitude= qSettings->value("defaultLongitude").toDouble();
bool useOpenGL= qSettings->value("useOpenGL").toBool();
bool showTileGridLines= qSettings->value("showTileGridLines").toBool();
QString accessMode= qSettings->value("accessMode").toString();
bool useMemoryCache= qSettings->value("useMemoryCache").toBool();
QString cacheLocation= qSettings->value("cacheLocation").toString();
QString uavSymbol=qSettings->value("uavSymbol").toString();
if (!mapProvider.isEmpty()) m_mapProvider = mapProvider;
m_defaultZoom = zoom;
m_defaultLatitude = latitude;
m_defaultLongitude = longitude;
m_useOpenGL = useOpenGL;
m_showTileGridLines = showTileGridLines;
m_uavSymbol=uavSymbol;
if (!accessMode.isEmpty()) m_accessMode = accessMode;
m_useMemoryCache = useMemoryCache;
if (!cacheLocation.isEmpty()) m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation);
}
}
IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone()
{
OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId());
m->m_mapProvider = m_mapProvider;
m->m_defaultZoom = m_defaultZoom;
m->m_defaultLatitude = m_defaultLatitude;
m->m_defaultLongitude = m_defaultLongitude;
m->m_useOpenGL = m_useOpenGL;
m->m_showTileGridLines = m_showTileGridLines;
m->m_accessMode = m_accessMode;
m->m_useMemoryCache = m_useMemoryCache;
m->m_cacheLocation = m_cacheLocation;
m->m_uavSymbol=m_uavSymbol;
return m;
}
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));
}
void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){
m_cacheLocation = cacheLocation;
}
/**
******************************************************************************
*
* @file opmapgadgetconfiguration.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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 "opmapgadgetconfiguration.h"
#include "utils/pathutils.h"
#include <QDir>
OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) :
IUAVGadgetConfiguration(classId, parent),
m_mapProvider("GoogleHybrid"),
m_defaultZoom(2),
m_defaultLatitude(0),
m_defaultLongitude(0),
m_useOpenGL(false),
m_showTileGridLines(false),
m_accessMode("ServerAndCache"),
m_useMemoryCache(true),
m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()),
m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")),
m_maxUpdateRate(2000) // ms
{
//if a saved configuration exists load it
if (qSettings != 0) {
QString mapProvider = qSettings->value("mapProvider").toString();
int zoom = qSettings->value("defaultZoom").toInt();
double latitude= qSettings->value("defaultLatitude").toDouble();
double longitude= qSettings->value("defaultLongitude").toDouble();
bool useOpenGL= qSettings->value("useOpenGL").toBool();
bool showTileGridLines= qSettings->value("showTileGridLines").toBool();
QString accessMode= qSettings->value("accessMode").toString();
bool useMemoryCache= qSettings->value("useMemoryCache").toBool();
QString cacheLocation= qSettings->value("cacheLocation").toString();
QString uavSymbol=qSettings->value("uavSymbol").toString();
int max_update_rate = qSettings->value("maxUpdateRate").toInt();
if (!mapProvider.isEmpty()) m_mapProvider = mapProvider;
m_defaultZoom = zoom;
m_defaultLatitude = latitude;
m_defaultLongitude = longitude;
m_useOpenGL = useOpenGL;
m_showTileGridLines = showTileGridLines;
m_uavSymbol = uavSymbol;
m_maxUpdateRate = max_update_rate;
if (m_maxUpdateRate < 100 || m_maxUpdateRate > 5000)
m_maxUpdateRate = 2000;
if (!accessMode.isEmpty())
m_accessMode = accessMode;
m_useMemoryCache = useMemoryCache;
if (!cacheLocation.isEmpty())
m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation);
}
}
IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone()
{
OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId());
m->m_mapProvider = m_mapProvider;
m->m_defaultZoom = m_defaultZoom;
m->m_defaultLatitude = m_defaultLatitude;
m->m_defaultLongitude = m_defaultLongitude;
m->m_useOpenGL = m_useOpenGL;
m->m_showTileGridLines = m_showTileGridLines;
m->m_accessMode = m_accessMode;
m->m_useMemoryCache = m_useMemoryCache;
m->m_cacheLocation = m_cacheLocation;
m->m_uavSymbol = m_uavSymbol;
m->m_maxUpdateRate = m_maxUpdateRate;
return m;
}
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
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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
*/
#ifndef OPMAP_GADGETCONFIGURATION_H
#define OPMAP_GADGETCONFIGURATION_H
#include <coreplugin/iuavgadgetconfiguration.h>
#include <QtCore/QString>
using namespace Core;
class OPMapGadgetConfiguration : public IUAVGadgetConfiguration
{
Q_OBJECT
Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider)
Q_PROPERTY(int zoommo READ zoom WRITE setZoom)
Q_PROPERTY(double latitude READ latitude WRITE setLatitude)
Q_PROPERTY(double longitude READ longitude WRITE setLongitude)
Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL)
Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines)
Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode)
Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache)
Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation)
Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol)
public:
explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone();
QString mapProvider() const { return m_mapProvider; }
int zoom() const { return m_defaultZoom; }
double latitude() const { return m_defaultLatitude; }
double longitude() const { return m_defaultLongitude; }
bool useOpenGL() const { return m_useOpenGL; }
bool showTileGridLines() const { return m_showTileGridLines; }
QString accessMode() const { return m_accessMode; }
bool useMemoryCache() const { return m_useMemoryCache; }
QString cacheLocation() const { return m_cacheLocation; }
QString uavSymbol() const { return m_uavSymbol; }
public slots:
void setMapProvider(QString provider) { m_mapProvider = provider; }
void setZoom(int zoom) { m_defaultZoom = zoom; }
void setLatitude(double latitude) { m_defaultLatitude = latitude; }
void setLongitude(double longitude) { m_defaultLongitude = longitude; }
void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; }
void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; }
void setAccessMode(QString accessMode) { m_accessMode = accessMode; }
void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; }
void setCacheLocation(QString cacheLocation);
void setUavSymbol(QString symbol){m_uavSymbol=symbol;}
private:
QString m_mapProvider;
int m_defaultZoom;
double m_defaultLatitude;
double m_defaultLongitude;
bool m_useOpenGL;
bool m_showTileGridLines;
QString m_accessMode;
bool m_useMemoryCache;
QString m_cacheLocation;
QString m_uavSymbol;
};
#endif // OPMAP_GADGETCONFIGURATION_H
/**
******************************************************************************
*
* @file opmapgadgetconfiguration.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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
*/
#ifndef OPMAP_GADGETCONFIGURATION_H
#define OPMAP_GADGETCONFIGURATION_H
#include <coreplugin/iuavgadgetconfiguration.h>
#include <QtCore/QString>
using namespace Core;
class OPMapGadgetConfiguration : public IUAVGadgetConfiguration
{
Q_OBJECT
Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider)
Q_PROPERTY(int zoommo READ zoom WRITE setZoom)
Q_PROPERTY(double latitude READ latitude WRITE setLatitude)
Q_PROPERTY(double longitude READ longitude WRITE setLongitude)
Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL)
Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines)
Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode)
Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache)
Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation)
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);
void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone();
QString mapProvider() const { return m_mapProvider; }
int zoom() const { return m_defaultZoom; }
double latitude() const { return m_defaultLatitude; }
double longitude() const { return m_defaultLongitude; }
bool useOpenGL() const { return m_useOpenGL; }
bool showTileGridLines() const { return m_showTileGridLines; }
QString accessMode() const { return m_accessMode; }
bool useMemoryCache() const { return m_useMemoryCache; }
QString cacheLocation() const { return m_cacheLocation; }
QString uavSymbol() const { return m_uavSymbol; }
int maxUpdateRate() const { return m_maxUpdateRate; }
public slots:
void setMapProvider(QString provider) { m_mapProvider = provider; }
void setZoom(int zoom) { m_defaultZoom = zoom; }
void setLatitude(double latitude) { m_defaultLatitude = latitude; }
void setLongitude(double longitude) { m_defaultLongitude = longitude; }
void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; }
void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; }
void setAccessMode(QString accessMode) { m_accessMode = accessMode; }
void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; }
void setCacheLocation(QString cacheLocation);
void setUavSymbol(QString symbol){m_uavSymbol=symbol;}
void setMaxUpdateRate(int update_rate){m_maxUpdateRate = update_rate;}
private:
QString m_mapProvider;
int m_defaultZoom;
double m_defaultLatitude;
double m_defaultLongitude;
bool m_useOpenGL;
bool m_showTileGridLines;
QString m_accessMode;
bool m_useMemoryCache;
QString m_cacheLocation;
QString m_uavSymbol;
int m_maxUpdateRate;
};
#endif // OPMAP_GADGETCONFIGURATION_H

View File

@ -1,133 +1,149 @@
/**
******************************************************************************
*
* @file opmapgadgetoptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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 "opmapgadgetoptionspage.h"
#include "opmapgadgetconfiguration.h"
#include <QtGui/QLabel>
#include <QtGui/QComboBox>
#include <QtGui/QSpinBox>
#include <QtGui/QDoubleSpinBox>
#include <QtGui/QHBoxLayout>
#include <QtGui/QVBoxLayout>
#include <QtGui/QFileDialog>
#include "opmapcontrol/opmapcontrol.h"
#include "utils/pathutils.h"
#include "ui_opmapgadgetoptionspage.h"
// *********************************************
OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) :
IOptionsPage(parent),
m_config(config)
{
}
QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent)
{
m_page = new Ui::OPMapGadgetOptionsPage();
QWidget *w = new QWidget(parent);
m_page->setupUi(w);
// populate the map provider combobox
m_page->providerComboBox->clear();
m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes());
// populate the access mode combobox
m_page->accessModeComboBox->clear();
m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes());
int index = m_page->providerComboBox->findText(m_config->mapProvider());
index = (index >= 0) ? index : 0;
m_page->providerComboBox->setCurrentIndex(index);
m_page->zoomSpinBox->setValue(m_config->zoom());
m_page->latitudeSpinBox->setValue(m_config->latitude());
m_page->longitudeSpinBox->setValue(m_config->longitude());
m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL());
m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines());
index = m_page->accessModeComboBox->findText(m_config->accessMode());
index = (index >= 0) ? index : 0;
m_page->accessModeComboBox->setCurrentIndex(index);
m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache());
m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory);
m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory"));
m_page->lineEditCacheLocation->setPath(m_config->cacheLocation());
QDir dir(":/uavs/images/");
QStringList list=dir.entryList();
foreach(QString i,list)
{
QIcon icon(QPixmap(":/uavs/images/"+i));
m_page->uavSymbolComboBox->addItem(icon,QString(),i);
}
for(int x=0;x<m_page->uavSymbolComboBox->count();++x)
{
if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol())
{
m_page->uavSymbolComboBox->setCurrentIndex(x);
}
}
connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked()));
return w;
}
void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked()
{
int index = m_page->accessModeComboBox->findText("ServerAndCache");
index = (index >= 0) ? index : 0;
m_page->accessModeComboBox->setCurrentIndex(index);
m_page->checkBoxUseMemoryCache->setChecked(true);
m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator());
}
void OPMapGadgetOptionsPage::apply()
{
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());
}
void OPMapGadgetOptionsPage::finish()
{
delete m_page;
}
/**
******************************************************************************
*
* @file opmapgadgetoptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup OPMapPlugin OpenPilot Map Plugin
* @{
* @brief The OpenPilot Map plugin
*****************************************************************************/
/*
* 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 "opmapgadgetoptionspage.h"
#include "opmapgadgetconfiguration.h"
#include <QtGui/QLabel>
#include <QtGui/QComboBox>
#include <QtGui/QSpinBox>
#include <QtGui/QDoubleSpinBox>
#include <QtGui/QHBoxLayout>
#include <QtGui/QVBoxLayout>
#include <QtGui/QFileDialog>
#include "opmapcontrol/opmapcontrol.h"
#include "utils/pathutils.h"
#include "ui_opmapgadgetoptionspage.h"
// *********************************************
OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) :
IOptionsPage(parent),
m_config(config)
{
}
QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent)
{
int index;
m_page = new Ui::OPMapGadgetOptionsPage();
QWidget *w = new QWidget(parent);
m_page->setupUi(w);
// populate the map provider combobox
m_page->providerComboBox->clear();
m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes());
// populate the access mode combobox
m_page->accessModeComboBox->clear();
m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes());
index = m_page->providerComboBox->findText(m_config->mapProvider());
index = (index >= 0) ? index : 0;
m_page->providerComboBox->setCurrentIndex(index);
// populate the map max update rate combobox
m_page->maxUpdateRateComboBox->clear();
m_page->maxUpdateRateComboBox->addItem("100ms", 100);
m_page->maxUpdateRateComboBox->addItem("200ms", 200);
m_page->maxUpdateRateComboBox->addItem("500ms", 500);
m_page->maxUpdateRateComboBox->addItem("1 sec", 1000);
m_page->maxUpdateRateComboBox->addItem("2 sec", 2000);
m_page->maxUpdateRateComboBox->addItem("5 sec", 5000);
index = m_page->maxUpdateRateComboBox->findData(m_config->maxUpdateRate());
index = (index >= 0) ? index : 4;
m_page->maxUpdateRateComboBox->setCurrentIndex(index);
m_page->zoomSpinBox->setValue(m_config->zoom());
m_page->latitudeSpinBox->setValue(m_config->latitude());
m_page->longitudeSpinBox->setValue(m_config->longitude());
m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL());
m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines());
index = m_page->accessModeComboBox->findText(m_config->accessMode());
index = (index >= 0) ? index : 0;
m_page->accessModeComboBox->setCurrentIndex(index);
m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache());
m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory);
m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory"));
m_page->lineEditCacheLocation->setPath(m_config->cacheLocation());
QDir dir(":/uavs/images/");
QStringList list=dir.entryList();
foreach(QString i,list)
{
QIcon icon(QPixmap(":/uavs/images/"+i));
m_page->uavSymbolComboBox->addItem(icon,QString(),i);
}
for(int x=0;x<m_page->uavSymbolComboBox->count();++x)
{
if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol())
{
m_page->uavSymbolComboBox->setCurrentIndex(x);
}
}
connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked()));
return w;
}
void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked()
{
int index = m_page->accessModeComboBox->findText("ServerAndCache");
index = (index >= 0) ? index : 0;
m_page->accessModeComboBox->setCurrentIndex(index);
m_page->checkBoxUseMemoryCache->setChecked(true);
m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator());
}
void OPMapGadgetOptionsPage::apply()
{
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>
</property>
<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">
<spacer name="horizontalSpacer_4">
<property name="orientation">
@ -249,6 +249,19 @@
</property>
</widget>
</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>
</item>
<item row="8" column="0">

View File

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

View File

@ -4,7 +4,7 @@
<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="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="YawBiasRate" units="channel" type="float" elements="1" defaultvalue="0.000001"/>
<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="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="PitchRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.0015,0,0.3"/>
<field name="YawRatePI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="0.003,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.002,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="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"/>