mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-29 07:24:13 +01:00
Merge branch 'revo' into revo-mini
Conflicts: androidgcs/AndroidManifest.xml androidgcs/res/layout/gcs_home.xml androidgcs/res/values/strings.xml androidgcs/src/org/openpilot/androidgcs/AttitudeView.java androidgcs/src/org/openpilot/androidgcs/HomePage.java flight/PipXtreme/System/pios_board.c ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp shared/uavobjectdefinition/taskinfo.xml
This commit is contained in:
commit
c9f66f5145
@ -65,24 +65,25 @@ static xQueueHandle queue;
|
||||
static xTaskHandle taskHandle;
|
||||
|
||||
static float lastResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0};
|
||||
static float lastFilteredResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0};
|
||||
static float filterAccumulator[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0};
|
||||
// used to inform the actuator thread that actuator update rate is changed
|
||||
static uint8_t updateRateChanged = 0;
|
||||
static volatile bool actuator_settings_updated;
|
||||
// used to inform the actuator thread that mixer settings are changed
|
||||
static volatile bool mixer_settings_updated;
|
||||
|
||||
// Private functions
|
||||
static void actuatorTask(void* parameters);
|
||||
static void actuator_update_rate(UAVObjEvent *);
|
||||
static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral);
|
||||
static void setFailsafe();
|
||||
static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings);
|
||||
static float MixerCurve(const float throttle, const float* curve, uint8_t elements);
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value);
|
||||
static void change_update_rate();
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings);
|
||||
static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update);
|
||||
static void MixerSettingsUpdatedCb(UAVObjEvent * ev);
|
||||
static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev);
|
||||
float ProcessMixer(const int index, const float curve1, const float curve2,
|
||||
MixerSettingsData* mixerSettings, ActuatorDesiredData* desired,
|
||||
const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired,
|
||||
const float period);
|
||||
|
||||
static uint16_t lastChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM] = {0,0,0,0};
|
||||
//this structure is equivalent to the UAVObjects for one mixer.
|
||||
typedef struct {
|
||||
uint8_t type;
|
||||
@ -109,22 +110,26 @@ int32_t ActuatorStart()
|
||||
*/
|
||||
int32_t ActuatorInitialize()
|
||||
{
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
// Register for notification of changes to ActuatorSettings
|
||||
ActuatorSettingsInitialize();
|
||||
ActuatorDesiredInitialize();
|
||||
MixerSettingsInitialize();
|
||||
ActuatorCommandInitialize();
|
||||
#if defined(DIAGNOSTICS)
|
||||
MixerStatusInitialize();
|
||||
#endif
|
||||
ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb);
|
||||
|
||||
// Listen for ExampleObject1 updates
|
||||
// Register for notification of changes to MixerSettings
|
||||
MixerSettingsInitialize();
|
||||
MixerSettingsConnectCallback(MixerSettingsUpdatedCb);
|
||||
|
||||
// Listen for ActuatorDesired updates (Primary input to this module)
|
||||
ActuatorDesiredInitialize();
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
ActuatorDesiredConnectQueue(queue);
|
||||
|
||||
// If settings change, update the output rate
|
||||
ActuatorSettingsConnectCallback(actuator_update_rate);
|
||||
// Primary output of this module
|
||||
ActuatorCommandInitialize();
|
||||
|
||||
#if defined(DIAGNOSTICS)
|
||||
// UAVO only used for inspecting the internal status of the mixer during debug
|
||||
MixerStatusInitialize();
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -151,22 +156,25 @@ static void actuatorTask(void* parameters)
|
||||
float dT = 0.0f;
|
||||
|
||||
ActuatorCommandData command;
|
||||
MixerSettingsData mixerSettings;
|
||||
ActuatorDesiredData desired;
|
||||
MixerStatusData mixerStatus;
|
||||
FlightStatusData flightStatus;
|
||||
|
||||
uint8_t MotorsSpinWhileArmed;
|
||||
int16_t ChannelMax[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
/* Read initial values of ActuatorSettings */
|
||||
ActuatorSettingsData actuatorSettings;
|
||||
actuator_settings_updated = false;
|
||||
ActuatorSettingsGet(&actuatorSettings);
|
||||
|
||||
change_update_rate();
|
||||
/* Read initial values of MixerSettings */
|
||||
MixerSettingsData mixerSettings;
|
||||
mixer_settings_updated = false;
|
||||
MixerSettingsGet(&mixerSettings);
|
||||
|
||||
float * status = (float *)&mixerStatus; //access status objects as an array of floats
|
||||
/* Force an initial configuration of the actuator update rates */
|
||||
actuator_update_rate_if_changed(&actuatorSettings, true);
|
||||
|
||||
// Go to the neutral (failsafe) values until an ActuatorDesired update is received
|
||||
setFailsafe();
|
||||
setFailsafe(&actuatorSettings, &mixerSettings);
|
||||
|
||||
// Main task loop
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
@ -174,17 +182,24 @@ static void actuatorTask(void* parameters)
|
||||
{
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
// Wait until the ActuatorDesired object is updated, if a timeout then go to failsafe
|
||||
if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE )
|
||||
{
|
||||
setFailsafe();
|
||||
continue;
|
||||
// Wait until the ActuatorDesired object is updated
|
||||
uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS);
|
||||
|
||||
/* Process settings updated events even in timeout case so we always act on the latest settings */
|
||||
if (actuator_settings_updated) {
|
||||
actuator_settings_updated = false;
|
||||
ActuatorSettingsGet (&actuatorSettings);
|
||||
actuator_update_rate_if_changed (&actuatorSettings, false);
|
||||
}
|
||||
if (mixer_settings_updated) {
|
||||
mixer_settings_updated = false;
|
||||
MixerSettingsGet (&mixerSettings);
|
||||
}
|
||||
|
||||
if(updateRateChanged!=0)
|
||||
{
|
||||
change_update_rate();
|
||||
updateRateChanged=0;
|
||||
if (rc != pdTRUE) {
|
||||
/* Update of ActuatorDesired timed out. Go to failsafe */
|
||||
setFailsafe(&actuatorSettings, &mixerSettings);
|
||||
continue;
|
||||
}
|
||||
|
||||
// Check how long since last update
|
||||
@ -194,18 +209,12 @@ static void actuatorTask(void* parameters)
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
MixerSettingsGet (&mixerSettings);
|
||||
ActuatorDesiredGet(&desired);
|
||||
ActuatorCommandGet(&command);
|
||||
|
||||
#if defined(DIAGNOSTICS)
|
||||
MixerStatusGet(&mixerStatus);
|
||||
#endif
|
||||
ActuatorSettingsMotorsSpinWhileArmedGet(&MotorsSpinWhileArmed);
|
||||
ActuatorSettingsChannelMaxGet(ChannelMax);
|
||||
ActuatorSettingsChannelMinGet(ChannelMin);
|
||||
ActuatorSettingsChannelNeutralGet(ChannelNeutral);
|
||||
|
||||
int nMixers = 0;
|
||||
Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type;
|
||||
for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++)
|
||||
@ -217,7 +226,7 @@ static void actuatorTask(void* parameters)
|
||||
}
|
||||
if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers.
|
||||
{
|
||||
setFailsafe(); // So that channels like PWM buzzer keep working
|
||||
setFailsafe(&actuatorSettings, &mixerSettings); // So that channels like PWM buzzer keep working
|
||||
continue;
|
||||
}
|
||||
|
||||
@ -225,7 +234,7 @@ static void actuatorTask(void* parameters)
|
||||
|
||||
bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED;
|
||||
bool positiveThrottle = desired.Throttle >= 0.00f;
|
||||
bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE;
|
||||
bool spinWhileArmed = actuatorSettings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE;
|
||||
|
||||
float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM);
|
||||
|
||||
@ -264,6 +273,8 @@ static void actuatorTask(void* parameters)
|
||||
break;
|
||||
}
|
||||
|
||||
float * status = (float *)&mixerStatus; //access status objects as an array of floats
|
||||
|
||||
for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++)
|
||||
{
|
||||
if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) {
|
||||
@ -337,9 +348,9 @@ static void actuatorTask(void* parameters)
|
||||
|
||||
for(int i = 0; i < MAX_MIX_ACTUATORS; i++)
|
||||
command.Channel[i] = scaleChannel(status[i],
|
||||
ChannelMax[i],
|
||||
ChannelMin[i],
|
||||
ChannelNeutral[i]);
|
||||
actuatorSettings.ChannelMax[i],
|
||||
actuatorSettings.ChannelMin[i],
|
||||
actuatorSettings.ChannelNeutral[i]);
|
||||
|
||||
// Store update time
|
||||
command.UpdateTime = 1000.0f*dT;
|
||||
@ -361,7 +372,7 @@ static void actuatorTask(void* parameters)
|
||||
|
||||
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n)
|
||||
{
|
||||
success &= set_channel(n, command.Channel[n]);
|
||||
success &= set_channel(n, command.Channel[n], &actuatorSettings);
|
||||
}
|
||||
|
||||
if(!success) {
|
||||
@ -379,15 +390,18 @@ static void actuatorTask(void* parameters)
|
||||
*Process mixing for one actuator
|
||||
*/
|
||||
float ProcessMixer(const int index, const float curve1, const float curve2,
|
||||
MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period)
|
||||
const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period)
|
||||
{
|
||||
Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects
|
||||
Mixer_t * mixer = &mixers[index];
|
||||
static float lastFilteredResult[MAX_MIX_ACTUATORS];
|
||||
const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects
|
||||
const Mixer_t * mixer = &mixers[index];
|
||||
|
||||
float result = (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1] / 128.0f) * curve1) +
|
||||
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) +
|
||||
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) +
|
||||
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) +
|
||||
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw);
|
||||
|
||||
if(mixer->type == MIXERSETTINGS_MIXER1TYPE_MOTOR)
|
||||
{
|
||||
if(result < 0.0f) //idle throttle
|
||||
@ -501,19 +515,13 @@ static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutr
|
||||
/**
|
||||
* Set actuator output to the neutral values (failsafe)
|
||||
*/
|
||||
static void setFailsafe()
|
||||
static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings)
|
||||
{
|
||||
/* grab only the modules parts that we are going to use */
|
||||
int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
ActuatorSettingsChannelMinGet(ChannelMin);
|
||||
int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
ActuatorSettingsChannelNeutralGet(ChannelNeutral);
|
||||
/* grab only the parts that we are going to use */
|
||||
int16_t Channel[ACTUATORCOMMAND_CHANNEL_NUMELEM];
|
||||
ActuatorCommandChannelGet(Channel);
|
||||
|
||||
MixerSettingsData mixerSettings;
|
||||
MixerSettingsGet (&mixerSettings);
|
||||
Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type; //pointer to array of mixers in UAVObjects
|
||||
const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects
|
||||
|
||||
// Reset ActuatorCommand to safe values
|
||||
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n)
|
||||
@ -521,11 +529,11 @@ static void setFailsafe()
|
||||
|
||||
if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR)
|
||||
{
|
||||
Channel[n] = ChannelMin[n];
|
||||
Channel[n] = actuatorSettings->ChannelMin[n];
|
||||
}
|
||||
else if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_SERVO)
|
||||
{
|
||||
Channel[n] = ChannelNeutral[n];
|
||||
Channel[n] = actuatorSettings->ChannelNeutral[n];
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -541,54 +549,22 @@ static void setFailsafe()
|
||||
// Update servo outputs
|
||||
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n)
|
||||
{
|
||||
set_channel(n, Channel[n]);
|
||||
set_channel(n, Channel[n], actuatorSettings);
|
||||
}
|
||||
|
||||
// Update output object's parts that we changed
|
||||
ActuatorCommandChannelSet(Channel);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Update the servo update rate
|
||||
*/
|
||||
static void actuator_update_rate(UAVObjEvent * ev)
|
||||
{
|
||||
uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM];
|
||||
// ActuatoSettings are not changed
|
||||
if ( ev->obj != ActuatorSettingsHandle() )
|
||||
return;
|
||||
|
||||
ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq);
|
||||
// check if the any rate setting is changed
|
||||
if (lastChannelUpdateFreq[0]!=0 && memcmp(&lastChannelUpdateFreq[0], &ChannelUpdateFreq[0], sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM) ==0)
|
||||
return;
|
||||
// signal to the actuator task that ChannelUpdateFreq are changed
|
||||
updateRateChanged = 1;
|
||||
}
|
||||
/**
|
||||
* @brief Change the update rates according to the ActuatorSettingsChannelUpdateFreq.
|
||||
*/
|
||||
static void change_update_rate()
|
||||
{
|
||||
uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM];
|
||||
// save the new rates
|
||||
ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq);
|
||||
memcpy(lastChannelUpdateFreq, ChannelUpdateFreq, sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM);
|
||||
PIOS_Servo_SetHz(&ChannelUpdateFreq[0], ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM);
|
||||
}
|
||||
|
||||
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
#else
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
|
||||
ActuatorSettingsData settings;
|
||||
ActuatorSettingsGet(&settings);
|
||||
|
||||
switch(settings.ChannelType[mixer_channel]) {
|
||||
static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings)
|
||||
{
|
||||
switch(actuatorSettings->ChannelType[mixer_channel]) {
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: {
|
||||
// This is for buzzers that take a PWM input
|
||||
|
||||
@ -631,18 +607,18 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
lastSysTime = thisSysTime;
|
||||
}
|
||||
}
|
||||
PIOS_Servo_Set( settings.ChannelAddr[mixer_channel],
|
||||
buzzOn?settings.ChannelMax[mixer_channel]:settings.ChannelMin[mixer_channel]);
|
||||
PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel],
|
||||
buzzOn?actuatorSettings->ChannelMax[mixer_channel]:actuatorSettings->ChannelMin[mixer_channel]);
|
||||
return true;
|
||||
}
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_PWM:
|
||||
PIOS_Servo_Set(settings.ChannelAddr[mixer_channel], value);
|
||||
PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], value);
|
||||
return true;
|
||||
#if defined(PIOS_INCLUDE_I2C_ESC)
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_MK:
|
||||
return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value);
|
||||
return PIOS_SetMKSpeed(actuatorSettings->ChannelAddr[mixer_channel],value);
|
||||
case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4:
|
||||
return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value);
|
||||
return PIOS_SetAstec4Speed(actuatorSettings->ChannelAddr[mixer_channel],value);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
@ -654,6 +630,35 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Update the servo update rate
|
||||
*/
|
||||
static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update)
|
||||
{
|
||||
static uint16_t prevChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM];
|
||||
|
||||
// check if the any rate setting is changed
|
||||
if (force_update ||
|
||||
memcmp (prevChannelUpdateFreq,
|
||||
actuatorSettings->ChannelUpdateFreq,
|
||||
sizeof(prevChannelUpdateFreq)) != 0) {
|
||||
/* Something has changed, apply the settings to HW */
|
||||
memcpy (prevChannelUpdateFreq,
|
||||
actuatorSettings->ChannelUpdateFreq,
|
||||
sizeof(prevChannelUpdateFreq));
|
||||
PIOS_Servo_SetHz(actuatorSettings->ChannelUpdateFreq, ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM);
|
||||
}
|
||||
}
|
||||
|
||||
static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev)
|
||||
{
|
||||
actuator_settings_updated = true;
|
||||
}
|
||||
|
||||
static void MixerSettingsUpdatedCb(UAVObjEvent * ev)
|
||||
{
|
||||
mixer_settings_updated = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -32,7 +32,7 @@
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_Servo_Init(void);
|
||||
extern void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t num_banks);
|
||||
extern void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t num_banks);
|
||||
extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position);
|
||||
|
||||
#endif /* PIOS_SERVO_H */
|
||||
|
@ -50,7 +50,7 @@ void PIOS_Servo_Init(void)
|
||||
* \param[in] onetofour Rate for outputs 1 to 4 (Hz)
|
||||
* \param[in] fivetoeight Rate for outputs 5 to 8 (Hz)
|
||||
*/
|
||||
void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks)
|
||||
void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -50,7 +50,7 @@ void PIOS_Servo_Init(void)
|
||||
* \param[in] onetofour Rate for outputs 1 to 4 (Hz)
|
||||
* \param[in] fivetoeight Rate for outputs 5 to 8 (Hz)
|
||||
*/
|
||||
void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks)
|
||||
void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg)
|
||||
* \param[in] array of rates in Hz
|
||||
* \param[in] maximum number of banks
|
||||
*/
|
||||
void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks)
|
||||
void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks)
|
||||
{
|
||||
if (!servo_cfg) {
|
||||
return;
|
||||
|
@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg)
|
||||
* \param[in] array of rates in Hz
|
||||
* \param[in] maximum number of banks
|
||||
*/
|
||||
void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks)
|
||||
void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks)
|
||||
{
|
||||
if (!servo_cfg) {
|
||||
return;
|
||||
|
@ -31,7 +31,7 @@
|
||||
#define PIOS_SERVO_H
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_Servo_SetHz(uint16_t * update_rates, uint8_t channels);
|
||||
extern void PIOS_Servo_SetHz(const uint16_t * update_rates, uint8_t banks);
|
||||
extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position);
|
||||
|
||||
#endif /* PIOS_SERVO_H */
|
||||
|
@ -280,6 +280,9 @@ static void eventTask()
|
||||
int32_t delayMs;
|
||||
EventCallbackInfo evInfo;
|
||||
|
||||
/* Must do this in task context to ensure that TaskMonitor has already finished its init */
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_EVENTDISPATCHER, eventTaskHandle);
|
||||
|
||||
// Initialize time
|
||||
timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS;
|
||||
|
||||
|
Binary file not shown.
@ -1 +1,20 @@
|
||||
#ifndef OPMAP_CONTROL_H_
|
||||
#define OPMAP_CONTROL_H_
|
||||
#include "src/mapwidget/opmapwidget.h"
|
||||
namespace mapcontrol
|
||||
{
|
||||
struct customData
|
||||
{
|
||||
float velocity;
|
||||
int mode;
|
||||
float mode_params[4];
|
||||
int condition;
|
||||
float condition_params[4];
|
||||
int command;
|
||||
int jumpdestination;
|
||||
int errordestination;
|
||||
};
|
||||
|
||||
}
|
||||
Q_DECLARE_METATYPE(mapcontrol::customData)
|
||||
#endif
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file accessmode.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file alllayersoftype.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file alllayersoftype.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cache.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cache.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cacheitemqueue.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file cacheitemqueue.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file diagnostics.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file diagnostics.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file geodecoderstatus.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file kibertilecache.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file kibertilecache.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file languagetype.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file languagetype.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file maptype.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file memorycache.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file memorycache.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file OPMaps.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file OPMaps.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file placemark.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file placemark.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file point.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file point.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file providerstrings.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file providerstrings.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureimage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureimage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureimagecache.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureimagecache.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rawtile.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rawtile.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file size.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file size.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tilecachequeue.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tilecachequeue.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file urlfactory.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file urlfactory.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file MouseWheelZoomType.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file copyrightstrings.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -31,11 +31,11 @@
|
||||
#include <QDateTime>
|
||||
|
||||
namespace internals {
|
||||
static const QString googleCopyright = QString("©%1 Google - Map data ©%1 Tele Atlas, Imagery ©%1 TerraMetrics").arg(QDate::currentDate().year());
|
||||
static const QString openStreetMapCopyright = QString("© OpenStreetMap - Map data ©%1 OpenStreetMap").arg(QDate::currentDate().year());
|
||||
static const QString yahooMapCopyright = QString("© Yahoo! Inc. - Map data & Imagery ©%1 NAVTEQ").arg(QDate::currentDate().year());
|
||||
static const QString virtualEarthCopyright = QString("©%1 Microsoft Corporation, ©%1 NAVTEQ, ©%1 Image courtesy of NASA").arg(QDate::currentDate().year());
|
||||
static const QString arcGisCopyright = QString("©%1 ESRI - Map data ©%1 ArcGIS").arg(QDate::currentDate().year());
|
||||
static const QString googleCopyright = QString("%1 Google - Map data %1 Tele Atlas, Imagery %1 TerraMetrics").arg(QDate::currentDate().year());
|
||||
static const QString openStreetMapCopyright = QString(" OpenStreetMap - Map data %1 OpenStreetMap").arg(QDate::currentDate().year());
|
||||
static const QString yahooMapCopyright = QString(" Yahoo! Inc. - Map data & Imagery %1 NAVTEQ").arg(QDate::currentDate().year());
|
||||
static const QString virtualEarthCopyright = QString("%1 Microsoft Corporation, %1 NAVTEQ, %1 Image courtesy of NASA").arg(QDate::currentDate().year());
|
||||
static const QString arcGisCopyright = QString("%1 ESRI - Map data %1 ArcGIS").arg(QDate::currentDate().year());
|
||||
|
||||
}
|
||||
#endif // COPYRIGHTSTRINGS_H
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file core.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -251,6 +251,7 @@ namespace internals {
|
||||
Matrix.Clear();
|
||||
GoToCurrentPositionOnZoom();
|
||||
UpdateBounds();
|
||||
keepInBounds();
|
||||
emit OnMapDrag();
|
||||
emit OnMapZoomChanged();
|
||||
emit OnNeedInvalidation();
|
||||
@ -572,7 +573,7 @@ namespace internals {
|
||||
{
|
||||
renderOffset.SetX(pt.X() - dragPoint.X());
|
||||
renderOffset.SetY(pt.Y() - dragPoint.Y());
|
||||
|
||||
keepInBounds();
|
||||
UpdateCenterTileXYLocation();
|
||||
|
||||
if(centerTileXYLocation != centerTileXYLocationLast)
|
||||
@ -692,4 +693,18 @@ namespace internals {
|
||||
pxRes1000km = (int) (1000000.0 / rez); // 1000km
|
||||
pxRes5000km = (int) (5000000.0 / rez); // 5000km
|
||||
}
|
||||
void Core::keepInBounds()
|
||||
{
|
||||
if(renderOffset.X()>0)
|
||||
renderOffset.SetX(0);
|
||||
if(renderOffset.Y()>0)
|
||||
renderOffset.SetY(0);
|
||||
int maxDragY=GetCurrentRegion().Height()-GettileRect().Height()*(maxOfTiles.Height()-minOfTiles.Height()+1);
|
||||
int maxDragX=GetCurrentRegion().Width()-GettileRect().Width()*(maxOfTiles.Width()-minOfTiles.Width()+1);
|
||||
|
||||
if(maxDragY>renderOffset.Y())
|
||||
renderOffset.SetY(maxDragY);
|
||||
if(maxDragX>renderOffset.X())
|
||||
renderOffset.SetX(maxDragX);
|
||||
}
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file core.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -193,6 +193,7 @@ namespace internals {
|
||||
bool isStarted(){return started;}
|
||||
|
||||
diagnostics GetDiagnostics();
|
||||
|
||||
signals:
|
||||
void OnCurrentPositionChanged(internals::PointLatLng point);
|
||||
void OnTileLoadComplete();
|
||||
@ -206,7 +207,7 @@ namespace internals {
|
||||
|
||||
private:
|
||||
|
||||
|
||||
void keepInBounds();
|
||||
PointLatLng currentPosition;
|
||||
core::Point currentPositionPixel;
|
||||
core::Point renderOffset;
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file loadtask.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file loadtask.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mousewheelzoomtype.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pointlatlng.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pointlatlng.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file lks94projection.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -614,6 +614,9 @@ double LKS94Projection::GetTileMatrixResolution(int const& zoom)
|
||||
|
||||
return ret;
|
||||
}
|
||||
/*
|
||||
* Returns the conversion from pixels to meters
|
||||
*/
|
||||
double LKS94Projection::GetGroundResolution(int const& zoom, double const& latitude)
|
||||
{
|
||||
Q_UNUSED(zoom);
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file lks94projection.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mercatorprojection.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mercatorprojection.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mercatorprojectionyandex.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mercatorprojectionyandex.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file platecarreeprojection.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file platecarreeprojection.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file platecarreeprojectionpergo.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file platecarreeprojectionpergo.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureprojection.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -103,6 +103,9 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom)
|
||||
|
||||
return ret;
|
||||
}
|
||||
/*
|
||||
* Returns the conversion from pixels to meters
|
||||
*/
|
||||
double PureProjection::GetGroundResolution(const int &zoom,const double &latitude)
|
||||
{
|
||||
return (cos(latitude * (PI / 180)) * 2 * PI * Axis()) / GetTileMatrixSizePixel(zoom).Width();
|
||||
@ -215,6 +218,18 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom)
|
||||
Lat /= (PI / 180);
|
||||
Lng /= (PI / 180);
|
||||
}
|
||||
double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2)
|
||||
{
|
||||
|
||||
double lon1=p1.Lng()* (M_PI / 180);
|
||||
double lat1=p1.Lat()* (M_PI / 180);
|
||||
double lon2=p2.Lng()* (M_PI / 180);
|
||||
double lat2=p2.Lat()* (M_PI / 180);
|
||||
|
||||
return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2),
|
||||
cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*M_PI);
|
||||
}
|
||||
|
||||
double PureProjection::DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2)
|
||||
{
|
||||
double R = 6371; // km
|
||||
@ -229,4 +244,34 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom)
|
||||
double d = R * c;
|
||||
return d;
|
||||
}
|
||||
|
||||
void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &distance,double &bearing)
|
||||
{
|
||||
distance=DistanceBetweenLatLng(p1,p2)*1000;
|
||||
bearing=courseBetweenLatLng(p1,p2);
|
||||
}
|
||||
|
||||
double PureProjection::myfmod(double x,double y)
|
||||
{
|
||||
return x - y*floor(x/y);
|
||||
}
|
||||
|
||||
PointLatLng PureProjection::translate(PointLatLng p1,double distance,double bearing)
|
||||
{
|
||||
PointLatLng ret;
|
||||
double d=distance;
|
||||
double tc=bearing;
|
||||
double lat1=p1.Lat()*M_PI/180;
|
||||
double lon1=p1.Lng()*M_PI/180;
|
||||
double R=6378137;
|
||||
double lat2 = asin(sin(lat1)*cos(d/R) + cos(lat1)*sin(d/R)*cos(tc) );
|
||||
double lon2 = lon1 + atan2(sin(tc)*sin(d/R)*cos(lat1),
|
||||
cos(d/R)-sin(lat1)*sin(lat2));
|
||||
lat2=lat2*180/M_PI;
|
||||
lon2=lon2*180/M_PI;
|
||||
ret.SetLat(lat2);
|
||||
ret.SetLng(lon2);
|
||||
return ret;
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pureprojection.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -33,7 +33,7 @@
|
||||
#include "pointlatlng.h"
|
||||
#include "cmath"
|
||||
#include "rectlatlng.h"
|
||||
|
||||
#include <QDebug>
|
||||
using namespace core;
|
||||
|
||||
namespace internals
|
||||
@ -81,6 +81,9 @@ public:
|
||||
void FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng);
|
||||
static double DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2);
|
||||
|
||||
PointLatLng translate(PointLatLng p1, double distance, double bearing);
|
||||
double courseBetweenLatLng(const PointLatLng &p1, const PointLatLng &p2);
|
||||
void offSetFromLatLngs(PointLatLng p1, PointLatLng p2, double &dX, double &dY);
|
||||
protected:
|
||||
|
||||
static const double PI;
|
||||
@ -103,7 +106,8 @@ protected:
|
||||
static double e3fn(const double &x);
|
||||
static double mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi);
|
||||
static qlonglong GetUTMzone(const double &lon);
|
||||
|
||||
private:
|
||||
double myfmod(double x, double y);
|
||||
};
|
||||
}
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rectangle.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rectangle.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rectlatlng.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rectlatlng.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file sizelatlng.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file sizelatlng.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tile.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tile.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tilematrix.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file tilematrix.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configuration.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A class that centralizes most of the mapcontrol configurations
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configuration.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A class that centralizes most of the mapcontrol configurations
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gpsitem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a UAV
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -37,27 +37,27 @@ namespace mapcontrol
|
||||
localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition());
|
||||
this->setPos(localposition.X(),localposition.Y());
|
||||
this->setZValue(4);
|
||||
trail=new QGraphicsItemGroup();
|
||||
trail=new QGraphicsItemGroup(this);
|
||||
trail->setParentItem(map);
|
||||
trailLine=new QGraphicsItemGroup();
|
||||
trailLine=new QGraphicsItemGroup(this);
|
||||
trailLine->setParentItem(map);
|
||||
this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
|
||||
mapfollowtype=UAVMapFollowType::None;
|
||||
trailtype=UAVTrailType::ByDistance;
|
||||
timer.start();
|
||||
connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos()));
|
||||
connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal)));
|
||||
}
|
||||
GPSItem::~GPSItem()
|
||||
{
|
||||
delete trail;
|
||||
|
||||
}
|
||||
|
||||
void GPSItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
Q_UNUSED(option);
|
||||
Q_UNUSED(widget);
|
||||
// painter->rotate(-90);
|
||||
painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic);
|
||||
// painter->drawRect(QRectF(-pic.width()/2,-pic.height()/2,pic.width()-1,pic.height()-1));
|
||||
}
|
||||
QRectF GPSItem::boundingRect()const
|
||||
{
|
||||
@ -74,9 +74,15 @@ namespace mapcontrol
|
||||
{
|
||||
if(timer.elapsed()>trailtime*1000)
|
||||
{
|
||||
trail->addToGroup(new TrailItem(position,altitude,Qt::green,this));
|
||||
TrailItem * ob=new TrailItem(position,altitude,Qt::green,map);
|
||||
trail->addToGroup(ob);
|
||||
connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT()));
|
||||
if(!lasttrailline.IsEmpty())
|
||||
trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::green,map)));
|
||||
{
|
||||
TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map);
|
||||
trailLine->addToGroup(obj);
|
||||
connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot()));
|
||||
}
|
||||
lasttrailline=position;
|
||||
timer.restart();
|
||||
}
|
||||
@ -86,10 +92,15 @@ namespace mapcontrol
|
||||
{
|
||||
if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position)*1000)>traildistance)
|
||||
{
|
||||
trail->addToGroup(new TrailItem(position,altitude,Qt::green,this));
|
||||
TrailItem * ob=new TrailItem(position,altitude,Qt::green,map);
|
||||
trail->addToGroup(ob);
|
||||
connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT()));
|
||||
if(!lasttrailline.IsEmpty())
|
||||
|
||||
trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::green,this)));
|
||||
{
|
||||
TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map);
|
||||
trailLine->addToGroup(obj);
|
||||
connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot()));
|
||||
}
|
||||
lasttrailline=position;
|
||||
lastcoord=position;
|
||||
}
|
||||
@ -97,48 +108,6 @@ namespace mapcontrol
|
||||
coord=position;
|
||||
this->altitude=altitude;
|
||||
RefreshPos();
|
||||
/*if(mapfollowtype==UAVMapFollowType::CenterAndRotateMap||mapfollowtype==UAVMapFollowType::CenterMap)
|
||||
{
|
||||
mapwidget->SetCurrentPosition(coord);
|
||||
}*/
|
||||
this->update();
|
||||
/*if(autosetreached)
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* wp=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(wp)
|
||||
{
|
||||
if(Distance3D(wp->Coord(),wp->Altitude())<autosetdistance)
|
||||
{
|
||||
wp->SetReached(true);
|
||||
emit UAVReachedWayPoint(wp->Number(),wp);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
if(mapwidget->Home!=0)
|
||||
{
|
||||
//verify if the UAV is inside the safety bouble
|
||||
if(Distance3D(mapwidget->Home->Coord(),mapwidget->Home->Altitude())>mapwidget->Home->SafeArea())
|
||||
{
|
||||
if(mapwidget->Home->safe!=false)
|
||||
{
|
||||
mapwidget->Home->safe=false;
|
||||
mapwidget->Home->update();
|
||||
emit UAVLeftSafetyBouble(this->coord);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if(mapwidget->Home->safe!=true)
|
||||
{
|
||||
mapwidget->Home->safe=true;
|
||||
mapwidget->Home->update();
|
||||
}
|
||||
}
|
||||
|
||||
}*/
|
||||
}
|
||||
}
|
||||
|
||||
@ -169,19 +138,14 @@ namespace mapcontrol
|
||||
{
|
||||
localposition=map->FromLatLngToLocal(coord);
|
||||
this->setPos(localposition.X(),localposition.Y());
|
||||
foreach(QGraphicsItem* i,trail->childItems())
|
||||
{
|
||||
TrailItem* w=qgraphicsitem_cast<TrailItem*>(i);
|
||||
if(w)
|
||||
w->setPos(map->FromLatLngToLocal(w->coord).X(),map->FromLatLngToLocal(w->coord).Y());
|
||||
}
|
||||
foreach(QGraphicsItem* i,trailLine->childItems())
|
||||
{
|
||||
TrailLineItem* ww=qgraphicsitem_cast<TrailLineItem*>(i);
|
||||
if(ww)
|
||||
ww->setLine(map->FromLatLngToLocal(ww->coord1).X(),map->FromLatLngToLocal(ww->coord1).Y(),map->FromLatLngToLocal(ww->coord2).X(),map->FromLatLngToLocal(ww->coord2).Y());
|
||||
emit setChildPosition();
|
||||
emit setChildLine();
|
||||
|
||||
}
|
||||
|
||||
void GPSItem::setOpacitySlot(qreal opacity)
|
||||
{
|
||||
setOpacity(opacity);
|
||||
}
|
||||
void GPSItem::SetTrailType(const UAVTrailType::Types &value)
|
||||
{
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gpsitem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a WayPoint
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -103,7 +103,6 @@ namespace mapcontrol
|
||||
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget);
|
||||
void RefreshPos();
|
||||
QRectF boundingRect() const;
|
||||
/**
|
||||
* @brief Sets the trail time to be used if TrailType is ByTimeElapsed
|
||||
@ -218,10 +217,13 @@ namespace mapcontrol
|
||||
// QRectF rect;
|
||||
|
||||
public slots:
|
||||
|
||||
void RefreshPos();
|
||||
void setOpacitySlot(qreal opacity);
|
||||
signals:
|
||||
void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint);
|
||||
void UAVLeftSafetyBouble(internals::PointLatLng const& position);
|
||||
void setChildPosition();
|
||||
void setChildLine();
|
||||
};
|
||||
}
|
||||
#endif // GPSITEM_H
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file homeitem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a trail point
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -27,17 +27,32 @@
|
||||
#include "homeitem.h"
|
||||
namespace mapcontrol
|
||||
{
|
||||
HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent),showsafearea(true),safearea(1000),altitude(0)
|
||||
HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent),
|
||||
showsafearea(true),safearea(1000),altitude(0),isDragging(false),toggleRefresh(true)
|
||||
{
|
||||
pic.load(QString::fromUtf8(":/markers/images/home2.svg"));
|
||||
pic=pic.scaled(30,30,Qt::IgnoreAspectRatio);
|
||||
this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
|
||||
this->setFlag(QGraphicsItem::ItemIsMovable,false);
|
||||
this->setFlag(QGraphicsItem::ItemIsSelectable,false);
|
||||
localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition());
|
||||
this->setPos(localposition.X(),localposition.Y());
|
||||
this->setZValue(4);
|
||||
coord=internals::PointLatLng(50,50);
|
||||
RefreshToolTip();
|
||||
setCacheMode(QGraphicsItem::DeviceCoordinateCache);
|
||||
connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos()));
|
||||
connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal)));
|
||||
}
|
||||
|
||||
void HomeItem::RefreshToolTip()
|
||||
{
|
||||
QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6);
|
||||
|
||||
setToolTip(QString("Waypoint: Home\nCoordinate:%1\nAltitude:%2\n").arg(coord_str).arg(QString::number(altitude)));
|
||||
}
|
||||
|
||||
|
||||
void HomeItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
Q_UNUSED(option);
|
||||
@ -56,7 +71,7 @@ namespace mapcontrol
|
||||
}
|
||||
QRectF HomeItem::boundingRect()const
|
||||
{
|
||||
if(!showsafearea)
|
||||
if(pic.width()>localsafearea*2 && !toggleRefresh)
|
||||
return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height());
|
||||
else
|
||||
return QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2);
|
||||
@ -67,6 +82,7 @@ namespace mapcontrol
|
||||
{
|
||||
return Type;
|
||||
}
|
||||
|
||||
void HomeItem::RefreshPos()
|
||||
{
|
||||
prepareGeometryChange();
|
||||
@ -75,6 +91,56 @@ namespace mapcontrol
|
||||
if(showsafearea)
|
||||
localsafearea=safearea/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat());
|
||||
|
||||
}
|
||||
RefreshToolTip();
|
||||
|
||||
this->update();
|
||||
toggleRefresh=false;
|
||||
|
||||
}
|
||||
|
||||
void HomeItem::setOpacitySlot(qreal opacity)
|
||||
{
|
||||
setOpacity(opacity);
|
||||
}
|
||||
|
||||
void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
if(event->button()==Qt::LeftButton)
|
||||
{
|
||||
isDragging=true;
|
||||
}
|
||||
QGraphicsItem::mousePressEvent(event);
|
||||
}
|
||||
|
||||
void HomeItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
if(event->button()==Qt::LeftButton)
|
||||
{
|
||||
coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y());
|
||||
isDragging=false;
|
||||
|
||||
emit homePositionChanged(coord,Altitude());
|
||||
}
|
||||
QGraphicsItem::mouseReleaseEvent(event);
|
||||
|
||||
RefreshToolTip();
|
||||
}
|
||||
void HomeItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
if(event->button()==Qt::LeftButton)
|
||||
{
|
||||
emit homedoubleclick(this);
|
||||
}
|
||||
}
|
||||
void HomeItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
|
||||
if(isDragging)
|
||||
{
|
||||
coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y());
|
||||
emit homePositionChanged(coord,Altitude());
|
||||
}
|
||||
QGraphicsItem::mouseMoveEvent(event);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file homeitem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a WayPoint
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -47,31 +47,41 @@ namespace mapcontrol
|
||||
QWidget *widget);
|
||||
QRectF boundingRect() const;
|
||||
int type() const;
|
||||
void RefreshPos();
|
||||
bool ShowSafeArea()const{return showsafearea;}
|
||||
void SetShowSafeArea(bool const& value){showsafearea=value;}
|
||||
void SetToggleRefresh(bool const& value){toggleRefresh=value;}
|
||||
int SafeArea()const{return safearea;}
|
||||
void SetSafeArea(int const& value){safearea=value;}
|
||||
bool safe;
|
||||
void SetCoord(internals::PointLatLng const& value){coord=value;}
|
||||
void SetCoord(internals::PointLatLng const& value){coord=value;emit homePositionChanged(value,Altitude());}
|
||||
internals::PointLatLng Coord()const{return coord;}
|
||||
void SetAltitude(int const& value){altitude=value;}
|
||||
int Altitude()const{return altitude;}
|
||||
void SetAltitude(float const& value){altitude=value;emit homePositionChanged(Coord(),Altitude());}
|
||||
float Altitude()const{return altitude;}
|
||||
void RefreshToolTip();
|
||||
private:
|
||||
|
||||
MapGraphicItem* map;
|
||||
OPMapWidget* mapwidget;
|
||||
QPixmap pic;
|
||||
core::Point localposition;
|
||||
internals::PointLatLng coord;
|
||||
bool showsafearea;
|
||||
bool toggleRefresh;
|
||||
int safearea;
|
||||
int localsafearea;
|
||||
int altitude;
|
||||
|
||||
float altitude;
|
||||
bool isDragging;
|
||||
protected:
|
||||
void mouseMoveEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mousePressEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event);
|
||||
public slots:
|
||||
|
||||
void RefreshPos();
|
||||
void setOpacitySlot(qreal opacity);
|
||||
signals:
|
||||
|
||||
void homePositionChanged(internals::PointLatLng coord,float);
|
||||
void homedoubleclick(HomeItem* waypoint);
|
||||
};
|
||||
}
|
||||
#endif // HOMEITEM_H
|
||||
|
Binary file not shown.
After Width: | Height: | Size: 4.3 KiB |
Binary file not shown.
After Width: | Height: | Size: 4.3 KiB |
Binary file not shown.
After Width: | Height: | Size: 1.6 KiB |
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapgraphicitem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief The main graphicsItem used on the widget, contains the map and map logic
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -42,10 +42,11 @@ namespace mapcontrol
|
||||
this->SetZoom(2);
|
||||
this->setFlag(ItemIsFocusable);
|
||||
connect(core,SIGNAL(OnNeedInvalidation()),this,SLOT(Core_OnNeedInvalidation()));
|
||||
connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh()));
|
||||
connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh()));
|
||||
//resize();
|
||||
connect(core,SIGNAL(OnMapDrag()),this,SLOT(childPosRefresh()));
|
||||
connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(childPosRefresh()));
|
||||
setCacheMode(QGraphicsItem::ItemCoordinateCache);
|
||||
}
|
||||
|
||||
void MapGraphicItem::start()
|
||||
{
|
||||
core->StartSystem();
|
||||
@ -78,39 +79,15 @@ namespace mapcontrol
|
||||
void MapGraphicItem::Core_OnNeedInvalidation()
|
||||
{
|
||||
this->update();
|
||||
foreach(QGraphicsItem* i,this->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
w->RefreshPos();
|
||||
UAVItem* ww=qgraphicsitem_cast<UAVItem*>(i);
|
||||
if(ww)
|
||||
ww->RefreshPos();
|
||||
HomeItem* www=qgraphicsitem_cast<HomeItem*>(i);
|
||||
if(www)
|
||||
www->RefreshPos();
|
||||
GPSItem* wwww=qgraphicsitem_cast<GPSItem*>(i);
|
||||
if(wwww)
|
||||
wwww->RefreshPos();
|
||||
emit childRefreshPosition();
|
||||
}
|
||||
}
|
||||
void MapGraphicItem::ChildPosRefresh()
|
||||
void MapGraphicItem::childPosRefresh()
|
||||
{
|
||||
foreach(QGraphicsItem* i,this->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
w->RefreshPos();
|
||||
UAVItem* ww=qgraphicsitem_cast<UAVItem*>(i);
|
||||
if(ww)
|
||||
ww->RefreshPos();
|
||||
HomeItem* www=qgraphicsitem_cast<HomeItem*>(i);
|
||||
if(www)
|
||||
www->RefreshPos();
|
||||
GPSItem* wwww=qgraphicsitem_cast<GPSItem*>(i);
|
||||
if(wwww)
|
||||
wwww->RefreshPos();
|
||||
emit childRefreshPosition();
|
||||
}
|
||||
void MapGraphicItem::setOverlayOpacity(qreal value)
|
||||
{
|
||||
emit childSetOpacity(value);
|
||||
}
|
||||
void MapGraphicItem::ConstructLastImage(int const& zoomdiff)
|
||||
{
|
||||
@ -118,8 +95,7 @@ namespace mapcontrol
|
||||
QSize size=boundingRect().size().toSize();
|
||||
size.setWidth(size.width()*2*zoomdiff);
|
||||
size.setHeight(size.height()*2*zoomdiff);
|
||||
temp=QImage(size,
|
||||
QImage::Format_ARGB32_Premultiplied);
|
||||
temp=QImage(size,QImage::Format_ARGB32_Premultiplied);
|
||||
temp.fill(0);
|
||||
QPainter imagePainter(&temp);
|
||||
imagePainter.translate(-boundingRect().topLeft());
|
||||
@ -216,7 +192,6 @@ namespace mapcontrol
|
||||
}
|
||||
void MapGraphicItem::mousePressEvent(QGraphicsSceneMouseEvent *event)
|
||||
{
|
||||
|
||||
if(!IsMouseOverMarker())
|
||||
{
|
||||
if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier)))
|
||||
@ -267,6 +242,7 @@ namespace mapcontrol
|
||||
if(!selectedArea.IsEmpty() && event->modifiers() == Qt::ShiftModifier)
|
||||
{
|
||||
SetZoomToFitRect(SelectedArea());
|
||||
selectedArea=internals::RectLatLng::Empty;
|
||||
}
|
||||
}
|
||||
|
||||
@ -276,6 +252,9 @@ namespace mapcontrol
|
||||
{
|
||||
if(event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier))
|
||||
this->setCursor(Qt::CrossCursor);
|
||||
if(event->key()==Qt::Key_Escape)
|
||||
selectedArea=internals::RectLatLng::Empty;
|
||||
QGraphicsItem::keyPressEvent(event);
|
||||
}
|
||||
void MapGraphicItem::keyReleaseEvent(QKeyEvent *event)
|
||||
{
|
||||
@ -388,7 +367,6 @@ namespace mapcontrol
|
||||
found = true;
|
||||
{
|
||||
painter->drawPixmap(core->tileRect.X(),core->tileRect.Y(), core->tileRect.Width(), core->tileRect.Height(),PureImageProxy::FromStream(img));
|
||||
// qDebug()<<"tile:"<<core->tileRect.X()<<core->tileRect.Y();
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -402,7 +380,6 @@ namespace mapcontrol
|
||||
painter->setFont(config->MissingDataFont);
|
||||
painter->setPen(Qt::red);
|
||||
painter->drawText(QRectF(core->tileRect.X(), core->tileRect.Y(), core->tileRect.Width(), core->tileRect.Height()),Qt::AlignCenter,(core->GettilePoint() == core->GetcenterTileXYLocation()? "CENTER: " :"TILE: ")+core->GettilePoint().ToString());
|
||||
//qDebug()<<"ShowTileGridLine:"<<core->GettilePoint().ToString()<<"=="<<core->GetcenterTileXYLocation().ToString();
|
||||
}
|
||||
}
|
||||
|
||||
@ -509,7 +486,6 @@ namespace mapcontrol
|
||||
float scaleValue = zoomDigi+remainder + 1;
|
||||
{
|
||||
MapRenderTransform = scaleValue;
|
||||
// qDebug()<<"scale="<<scaleValue<<"zoomdigi:"<<ZoomDigi()<<"integer:"<<integer;
|
||||
}
|
||||
if(integer>MaxZoom())
|
||||
integer=MaxZoom();
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapgraphicitem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief The main graphicsItem used on the widget, contains the map and map logic
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -40,8 +40,10 @@
|
||||
#include <QObject>
|
||||
#include "waypointitem.h"
|
||||
//#include "uavitem.h"
|
||||
|
||||
namespace mapcontrol
|
||||
{
|
||||
class WayPointItem;
|
||||
class OPMapWidget;
|
||||
/**
|
||||
* @brief The main graphicsItem used on the widget, contains the map and map logic
|
||||
@ -92,7 +94,6 @@ namespace mapcontrol
|
||||
bool IsDragging()const{return core->IsDragging();}
|
||||
|
||||
QImage lastimage;
|
||||
// QPainter* imagePainter;
|
||||
core::Point lastimagepoint;
|
||||
void paintImage(QPainter* painter);
|
||||
void ConstructLastImage(int const& zoomdiff);
|
||||
@ -100,7 +101,7 @@ namespace mapcontrol
|
||||
double Zoom();
|
||||
double ZoomDigi();
|
||||
double ZoomTotal();
|
||||
|
||||
void setOverlayOpacity(qreal value);
|
||||
protected:
|
||||
void mouseMoveEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mousePressEvent ( QGraphicsSceneMouseEvent * event );
|
||||
@ -199,7 +200,7 @@ namespace mapcontrol
|
||||
void SetMapType(MapType::Types const& value){core->SetMapType(value);}
|
||||
private slots:
|
||||
void Core_OnNeedInvalidation();
|
||||
void ChildPosRefresh();
|
||||
void childPosRefresh();
|
||||
public slots:
|
||||
/**
|
||||
* @brief To be called when the scene size changes
|
||||
@ -213,7 +214,10 @@ namespace mapcontrol
|
||||
*
|
||||
* @param zoom
|
||||
*/
|
||||
void wpdoubleclicked(WayPointItem * wp);
|
||||
void zoomChanged(double zoomtotal,double zoomreal,double zoomdigi);
|
||||
void childRefreshPosition();
|
||||
void childSetOpacity(qreal value);
|
||||
};
|
||||
}
|
||||
#endif // MAPGRAPHICITEM_H
|
||||
|
@ -12,6 +12,9 @@
|
||||
<file>images/mapquad.png</file>
|
||||
<file>images/dragons1.jpg</file>
|
||||
<file>images/dragons2.jpeg</file>
|
||||
<file>images/waypoint_marker1.png</file>
|
||||
<file>images/waypoint_marker2.png</file>
|
||||
<file>images/waypoint_marker3.png</file>
|
||||
</qresource>
|
||||
<qresource prefix="/uavs">
|
||||
<file>images/airplanepip.png</file>
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapripform.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Form to be used with the MapRipper class
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapripform.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Form to be used with the MapRipper class
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapripper.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A class that allows ripping of a selection of the map
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -49,7 +49,11 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect)
|
||||
emit numberOfTilesChanged(0,0);
|
||||
}
|
||||
else
|
||||
QMessageBox::information(new QWidget(),"No valid selection","Please select the area of the map to rip with Mouse+Control key");
|
||||
#ifdef Q_OS_DARWIN
|
||||
QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with <COMMAND>+Left mouse click");
|
||||
#else
|
||||
QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with <CTRL>+Left mouse click");
|
||||
#endif
|
||||
}
|
||||
void MapRipper::finish()
|
||||
{
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file mapripper.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A class that allows ripping of a selection of the map
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
|
@ -14,7 +14,9 @@ SOURCES += mapgraphicitem.cpp \
|
||||
homeitem.cpp \
|
||||
mapripform.cpp \
|
||||
mapripper.cpp \
|
||||
traillineitem.cpp
|
||||
traillineitem.cpp \
|
||||
waypointline.cpp \
|
||||
waypointcircle.cpp
|
||||
|
||||
LIBS += -L../build \
|
||||
-lcore \
|
||||
@ -39,7 +41,9 @@ HEADERS += mapgraphicitem.h \
|
||||
homeitem.h \
|
||||
mapripform.h \
|
||||
mapripper.h \
|
||||
traillineitem.h
|
||||
traillineitem.h \
|
||||
waypointline.h \
|
||||
waypointcircle.h
|
||||
QT += opengl
|
||||
QT += network
|
||||
QT += sql
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file opmapwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief The Map Widget, this is the part exposed to the user
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -33,13 +33,18 @@
|
||||
namespace mapcontrol
|
||||
{
|
||||
|
||||
OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0),followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0)
|
||||
OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0)
|
||||
,followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0),overlayOpacity(1)
|
||||
{
|
||||
setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred);
|
||||
core=new internals::Core;
|
||||
map=new MapGraphicItem(core,config);
|
||||
mscene.addItem(map);
|
||||
this->setScene(&mscene);
|
||||
Home=new HomeItem(map,this);
|
||||
Home->setParentItem(map);
|
||||
Home->setZValue(-1);
|
||||
setStyleSheet("QToolTip {font-size:8pt; color:blue;opacity: 223; padding:2px; border-width:2px; border-style:solid; border-color: rgb(170, 170, 127);border-radius:4px }");
|
||||
this->adjustSize();
|
||||
connect(map,SIGNAL(zoomChanged(double,double,double)),this,SIGNAL(zoomChanged(double,double,double)));
|
||||
connect(map->core,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)),this,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)));
|
||||
@ -50,10 +55,12 @@ namespace mapcontrol
|
||||
connect(map->core,SIGNAL(OnTileLoadComplete()),this,SIGNAL(OnTileLoadComplete()));
|
||||
connect(map->core,SIGNAL(OnTileLoadStart()),this,SIGNAL(OnTileLoadStart()));
|
||||
connect(map->core,SIGNAL(OnTilesStillToLoad(int)),this,SIGNAL(OnTilesStillToLoad(int)));
|
||||
connect(map,SIGNAL(wpdoubleclicked(WayPointItem*)),this,SIGNAL(OnWayPointDoubleClicked(WayPointItem*)));
|
||||
connect(&mscene,SIGNAL(selectionChanged()),this,SLOT(OnSelectionChanged()));
|
||||
SetShowDiagnostics(showDiag);
|
||||
this->setMouseTracking(followmouse);
|
||||
SetShowCompass(true);
|
||||
|
||||
QPixmapCache::setCacheLimit(64*1024);
|
||||
}
|
||||
void OPMapWidget::SetShowDiagnostics(bool const& value)
|
||||
{
|
||||
@ -70,12 +77,24 @@ namespace mapcontrol
|
||||
delete diagTimer;
|
||||
diagTimer=0;
|
||||
}
|
||||
|
||||
if(GPS!=0)
|
||||
{
|
||||
delete GPS;
|
||||
GPS=0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
diagTimer=new QTimer();
|
||||
connect(diagTimer,SIGNAL(timeout()),this,SLOT(diagRefresh()));
|
||||
diagTimer->start(500);
|
||||
if(GPS==0)
|
||||
{
|
||||
GPS=new GPSItem(map,this);
|
||||
GPS->setParentItem(map);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
@ -85,8 +104,40 @@ namespace mapcontrol
|
||||
UAV->SetUavPic(UAVPic);
|
||||
if(GPS!=0)
|
||||
GPS->SetUavPic(UAVPic);
|
||||
}
|
||||
|
||||
WayPointLine * OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to,QColor color)
|
||||
{
|
||||
if(!from|!to)
|
||||
return NULL;
|
||||
WayPointLine* ret= new WayPointLine(from,to,map,color);
|
||||
ret->setOpacity(overlayOpacity);
|
||||
return ret;
|
||||
}
|
||||
WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to,QColor color)
|
||||
{
|
||||
if(!from|!to)
|
||||
return NULL;
|
||||
WayPointLine* ret= new WayPointLine(from,to,map,color);
|
||||
ret->setOpacity(overlayOpacity);
|
||||
return ret;
|
||||
}
|
||||
WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise,QColor color)
|
||||
{
|
||||
if(!center|!radius)
|
||||
return NULL;
|
||||
WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color);
|
||||
ret->setOpacity(overlayOpacity);
|
||||
return ret;
|
||||
}
|
||||
|
||||
WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise,QColor color)
|
||||
{
|
||||
if(!center|!radius)
|
||||
return NULL;
|
||||
WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color);
|
||||
ret->setOpacity(overlayOpacity);
|
||||
return ret;
|
||||
}
|
||||
void OPMapWidget::SetShowUAV(const bool &value)
|
||||
{
|
||||
@ -96,47 +147,21 @@ namespace mapcontrol
|
||||
UAV->setParentItem(map);
|
||||
connect(this,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng)),UAV,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng)));
|
||||
connect(this,SIGNAL(UAVReachedWayPoint(int,WayPointItem*)),UAV,SIGNAL(UAVReachedWayPoint(int,WayPointItem*)));
|
||||
UAV->setOpacity(overlayOpacity);
|
||||
}
|
||||
else if(!value)
|
||||
{
|
||||
if(UAV!=0)
|
||||
{
|
||||
delete UAV;
|
||||
UAV=0;
|
||||
}
|
||||
|
||||
}
|
||||
if(value && GPS==0)
|
||||
{
|
||||
GPS=new GPSItem(map,this);
|
||||
GPS->setParentItem(map);
|
||||
}
|
||||
else if(!value)
|
||||
{
|
||||
if(GPS!=0)
|
||||
{
|
||||
delete GPS;
|
||||
GPS=0;
|
||||
UAV=NULL;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
void OPMapWidget::SetShowHome(const bool &value)
|
||||
{
|
||||
if(value && Home==0)
|
||||
{
|
||||
Home=new HomeItem(map,this);
|
||||
Home->setParentItem(map);
|
||||
}
|
||||
else if(!value)
|
||||
{
|
||||
if(Home!=0)
|
||||
{
|
||||
delete Home;
|
||||
Home=0;
|
||||
}
|
||||
|
||||
}
|
||||
Home->setVisible(value);
|
||||
}
|
||||
|
||||
void OPMapWidget::resizeEvent(QResizeEvent *event)
|
||||
@ -161,13 +186,19 @@ namespace mapcontrol
|
||||
}
|
||||
OPMapWidget::~OPMapWidget()
|
||||
{
|
||||
if(UAV)
|
||||
delete UAV;
|
||||
if(Home)
|
||||
delete Home;
|
||||
if(map)
|
||||
delete map;
|
||||
if(core)
|
||||
delete core;
|
||||
if(configuration)
|
||||
delete configuration;
|
||||
foreach(QGraphicsItem* i,this->items())
|
||||
{
|
||||
if(i)
|
||||
delete i;
|
||||
}
|
||||
}
|
||||
@ -203,18 +234,33 @@ namespace mapcontrol
|
||||
WayPointItem* item=new WayPointItem(this->CurrentPosition(),0,map);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
int position=item->Number();
|
||||
emit WPCreated(position,item);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::magicWPCreate()
|
||||
{
|
||||
WayPointItem* item=new WayPointItem(map,true);
|
||||
item->SetShowNumber(false);
|
||||
item->setParentItem(map);
|
||||
return item;
|
||||
}
|
||||
void OPMapWidget::WPCreate(WayPointItem* item)
|
||||
{
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
int position=item->Number();
|
||||
emit WPCreated(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude)
|
||||
{
|
||||
WayPointItem* item=new WayPointItem(coord,altitude,map);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
int position=item->Number();
|
||||
emit WPCreated(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude, QString const& description)
|
||||
@ -222,6 +268,19 @@ namespace mapcontrol
|
||||
WayPointItem* item=new WayPointItem(coord,altitude,description,map);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
int position=item->Number();
|
||||
emit WPCreated(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPCreate(const distBearingAltitude &relativeCoord, const QString &description)
|
||||
{
|
||||
WayPointItem* item=new WayPointItem(relativeCoord,description,map);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
int position=item->Number();
|
||||
emit WPCreated(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPInsert(const int &position)
|
||||
@ -231,6 +290,7 @@ namespace mapcontrol
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
emit WPInserted(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
void OPMapWidget::WPInsert(WayPointItem* item,const int &position)
|
||||
@ -239,7 +299,7 @@ namespace mapcontrol
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
emit WPInserted(position,item);
|
||||
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPInsert(internals::PointLatLng const& coord,int const& altitude,const int &position)
|
||||
{
|
||||
@ -248,29 +308,131 @@ namespace mapcontrol
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
emit WPInserted(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPInsert(internals::PointLatLng const& coord,int const& altitude, QString const& description,const int &position)
|
||||
{
|
||||
WayPointItem* item=new WayPointItem(coord,altitude,description,map);
|
||||
internals::PointLatLng mcoord;
|
||||
bool reloc=false;
|
||||
if(mcoord==internals::PointLatLng(0,0))
|
||||
{
|
||||
mcoord=CurrentPosition();
|
||||
reloc=true;
|
||||
}
|
||||
else
|
||||
mcoord=coord;
|
||||
WayPointItem* item=new WayPointItem(mcoord,altitude,description,map);
|
||||
item->SetNumber(position);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
emit WPInserted(position,item);
|
||||
if(reloc)
|
||||
emit WPValuesChanged(item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
WayPointItem* OPMapWidget::WPInsert(distBearingAltitude const& relative, QString const& description,const int &position)
|
||||
{
|
||||
WayPointItem* item=new WayPointItem(relative,description,map);
|
||||
item->SetNumber(position);
|
||||
ConnectWP(item);
|
||||
item->setParentItem(map);
|
||||
emit WPInserted(position,item);
|
||||
setOverlayOpacity(overlayOpacity);
|
||||
return item;
|
||||
}
|
||||
void OPMapWidget::WPDelete(WayPointItem *item)
|
||||
{
|
||||
emit WPDeleted(item->Number());
|
||||
emit WPDeleted(item->Number(),item);
|
||||
delete item;
|
||||
}
|
||||
void OPMapWidget::WPDeleteAll()
|
||||
void OPMapWidget::WPDelete(int number)
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
{
|
||||
if(w->Number()==number)
|
||||
{
|
||||
emit WPDeleted(w->Number(),w);
|
||||
delete w;
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
WayPointItem * OPMapWidget::WPFind(int number)
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
{
|
||||
if(w->Number()==number)
|
||||
{
|
||||
return w;
|
||||
}
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
void OPMapWidget::WPSetVisibleAll(bool value)
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
{
|
||||
if(w->Number()!=-1)
|
||||
w->setVisible(value);
|
||||
}
|
||||
}
|
||||
}
|
||||
void OPMapWidget::WPDeleteAll()
|
||||
{
|
||||
int x=0;
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
{
|
||||
if(w->Number()!=-1)
|
||||
{
|
||||
emit WPDeleted(w->Number(),w);
|
||||
delete w;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
bool OPMapWidget::WPPresent()
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointItem* w=qgraphicsitem_cast<WayPointItem*>(i);
|
||||
if(w)
|
||||
{
|
||||
if(w->Number()!=-1)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
void OPMapWidget::deleteAllOverlays()
|
||||
{
|
||||
foreach(QGraphicsItem* i,map->childItems())
|
||||
{
|
||||
WayPointLine* w=qgraphicsitem_cast<WayPointLine*>(i);
|
||||
if(w)
|
||||
w->deleteLater();
|
||||
else
|
||||
{
|
||||
WayPointCircle* ww=qgraphicsitem_cast<WayPointCircle*>(i);
|
||||
if(ww)
|
||||
ww->deleteLater();
|
||||
}
|
||||
}
|
||||
}
|
||||
QList<WayPointItem*> OPMapWidget::WPSelected()
|
||||
@ -291,11 +453,13 @@ namespace mapcontrol
|
||||
|
||||
void OPMapWidget::ConnectWP(WayPointItem *item)
|
||||
{
|
||||
connect(item,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)));
|
||||
connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*)));
|
||||
connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*)));
|
||||
connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*)));
|
||||
connect(this,SIGNAL(WPDeleted(int)),item,SLOT(WPDeleted(int)));
|
||||
connect(item,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),Qt::DirectConnection);
|
||||
connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*)),Qt::DirectConnection);
|
||||
connect(item,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SIGNAL(WPLocalPositionChanged(QPointF,WayPointItem*)),Qt::DirectConnection);
|
||||
connect(item,SIGNAL(manualCoordChange(WayPointItem*)),this,SIGNAL(WPManualCoordChange(WayPointItem*)),Qt::DirectConnection);
|
||||
connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*)),Qt::DirectConnection);
|
||||
connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*)),Qt::DirectConnection);
|
||||
connect(this,SIGNAL(WPDeleted(int,WayPointItem*)),item,SLOT(WPDeleted(int,WayPointItem*)),Qt::DirectConnection);
|
||||
}
|
||||
void OPMapWidget::diagRefresh()
|
||||
{
|
||||
@ -329,12 +493,12 @@ namespace mapcontrol
|
||||
compass->setScale(0.1+0.05*(qreal)(this->size().width())/1000*(qreal)(this->size().height())/600);
|
||||
// compass->setTransformOriginPoint(compass->boundingRect().width(),compass->boundingRect().height());
|
||||
compass->setFlag(QGraphicsItem::ItemIsMovable,true);
|
||||
compass->setFlag(QGraphicsItem::ItemIsSelectable,true);
|
||||
mscene.addItem(compass);
|
||||
compass->setTransformOriginPoint(compass->boundingRect().width()/2,compass->boundingRect().height()/2);
|
||||
compass->setPos(55-compass->boundingRect().width()/2,55-compass->boundingRect().height()/2);
|
||||
compass->setZValue(3);
|
||||
compass->setOpacity(0.7);
|
||||
|
||||
}
|
||||
if(!value && compass)
|
||||
{
|
||||
@ -342,6 +506,12 @@ namespace mapcontrol
|
||||
compass=0;
|
||||
}
|
||||
}
|
||||
|
||||
void OPMapWidget::setOverlayOpacity(qreal value)
|
||||
{
|
||||
map->setOverlayOpacity(value);
|
||||
overlayOpacity=value;
|
||||
}
|
||||
void OPMapWidget::SetRotate(qreal const& value)
|
||||
{
|
||||
map->mapRotate(value);
|
||||
@ -353,4 +523,28 @@ namespace mapcontrol
|
||||
{
|
||||
new MapRipper(core,map->SelectedArea());
|
||||
}
|
||||
|
||||
void OPMapWidget::setSelectedWP(QList<WayPointItem * >list)
|
||||
{
|
||||
this->scene()->clearSelection();
|
||||
foreach(WayPointItem * wp,list)
|
||||
{
|
||||
wp->setSelected(true);
|
||||
}
|
||||
}
|
||||
|
||||
void OPMapWidget::OnSelectionChanged()
|
||||
{
|
||||
QList<QGraphicsItem*> list;
|
||||
QList<WayPointItem*> wplist;
|
||||
list=this->scene()->selectedItems();
|
||||
foreach(QGraphicsItem* item,list)
|
||||
{
|
||||
WayPointItem * wp=qgraphicsitem_cast<WayPointItem*>(item);
|
||||
if(wp)
|
||||
wplist.append(wp);
|
||||
}
|
||||
if(wplist.length()>0)
|
||||
emit selectedWPChanged(wplist);
|
||||
}
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file opmapwidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief The Map Widget, this is the part exposed to the user
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -41,6 +41,9 @@
|
||||
#include "gpsitem.h"
|
||||
#include "homeitem.h"
|
||||
#include "mapripper.h"
|
||||
#include "waypointline.h"
|
||||
#include "waypointcircle.h"
|
||||
#include "waypointitem.h"
|
||||
namespace mapcontrol
|
||||
{
|
||||
class UAVItem;
|
||||
@ -279,6 +282,15 @@ namespace mapcontrol
|
||||
*/
|
||||
WayPointItem* WPCreate(internals::PointLatLng const& coord,int const& altitude, QString const& description);
|
||||
/**
|
||||
* @brief Creates a new WayPoint
|
||||
*
|
||||
* @param coord the offset in meters to the home position
|
||||
* @param altitude the Altitude of the WayPoint
|
||||
* @param description the description of the WayPoint
|
||||
* @return WayPointItem a pointer to the WayPoint created
|
||||
*/
|
||||
WayPointItem *WPCreate(const distBearingAltitude &relativeCoord, const QString &description);
|
||||
/**
|
||||
* @brief Inserts a new WayPoint on the specified position
|
||||
*
|
||||
* @param position index of the WayPoint
|
||||
@ -311,6 +323,7 @@ namespace mapcontrol
|
||||
* @return WayPointItem a pointer to the WayPoint Inserted
|
||||
*/
|
||||
WayPointItem* WPInsert(internals::PointLatLng const& coord,int const& altitude, QString const& description,int const& position);
|
||||
WayPointItem *WPInsert(const distBearingAltitude &relative, const QString &description, const int &position);
|
||||
|
||||
/**
|
||||
* @brief Deletes the WayPoint
|
||||
@ -340,6 +353,8 @@ namespace mapcontrol
|
||||
|
||||
void SetShowCompass(bool const& value);
|
||||
|
||||
void setOverlayOpacity(qreal value);
|
||||
|
||||
UAVItem* UAV;
|
||||
GPSItem* GPS;
|
||||
HomeItem* Home;
|
||||
@ -349,6 +364,17 @@ namespace mapcontrol
|
||||
bool ShowHome()const{return showhome;}
|
||||
void SetShowDiagnostics(bool const& value);
|
||||
void SetUavPic(QString UAVPic);
|
||||
WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to, QColor color);
|
||||
WayPointLine * WPLineCreate(HomeItem *from,WayPointItem *to, QColor color);
|
||||
WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise,QColor color);
|
||||
WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise,QColor color);
|
||||
void deleteAllOverlays();
|
||||
void WPSetVisibleAll(bool value);
|
||||
WayPointItem *magicWPCreate();
|
||||
bool WPPresent();
|
||||
void WPDelete(int number);
|
||||
WayPointItem *WPFind(int number);
|
||||
void setSelectedWP(QList<WayPointItem *> list);
|
||||
private:
|
||||
internals::Core *core;
|
||||
MapGraphicItem *map;
|
||||
@ -366,6 +392,7 @@ namespace mapcontrol
|
||||
QTimer * diagTimer;
|
||||
QGraphicsTextItem * diagGraphItem;
|
||||
bool showDiag;
|
||||
qreal overlayOpacity;
|
||||
private slots:
|
||||
void diagRefresh();
|
||||
// WayPointItem* item;//apagar
|
||||
@ -398,6 +425,9 @@ namespace mapcontrol
|
||||
* @param waypoint WayPoint inserted
|
||||
*/
|
||||
void WPReached(WayPointItem* waypoint);
|
||||
|
||||
void WPCreated(int const& number,WayPointItem* waypoint);
|
||||
|
||||
/**
|
||||
* @brief Fires when a new WayPoint is inserted
|
||||
*
|
||||
@ -410,7 +440,10 @@ namespace mapcontrol
|
||||
*
|
||||
* @param number number of the deleted WayPoint
|
||||
*/
|
||||
void WPDeleted(int const& number);
|
||||
void WPDeleted(int const& number,WayPointItem* waypoint);
|
||||
|
||||
void WPLocalPositionChanged(QPointF,WayPointItem*);
|
||||
void WPManualCoordChange(WayPointItem*);
|
||||
/**
|
||||
* @brief Fires When a WayPoint is Reached
|
||||
*
|
||||
@ -469,11 +502,14 @@ namespace mapcontrol
|
||||
* @param number the number of tiles still in the queue
|
||||
*/
|
||||
void OnTilesStillToLoad(int number);
|
||||
void OnWayPointDoubleClicked(WayPointItem * waypoint);
|
||||
void selectedWPChanged(QList<WayPointItem*>);
|
||||
public slots:
|
||||
/**
|
||||
* @brief Ripps the current selection to the DB
|
||||
*/
|
||||
void RipMap();
|
||||
void OnSelectionChanged();
|
||||
|
||||
};
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file trailitem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a trail point
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -28,9 +28,8 @@
|
||||
#include <QDateTime>
|
||||
namespace mapcontrol
|
||||
{
|
||||
TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, QGraphicsItem* parent):QGraphicsItem(parent),coord(coord)
|
||||
TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, MapGraphicItem *map):QGraphicsItem(map),coord(coord),m_brush(color),m_map(map)
|
||||
{
|
||||
m_brush=color;
|
||||
QDateTime time=QDateTime::currentDateTime();
|
||||
QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6);
|
||||
setToolTip(QString(tr("Position:")+"%1\n"+tr("Altitude:")+"%2\n"+tr("Time:")+"%3").arg(coord_str).arg(QString::number(altitude)).arg(time.toString()));
|
||||
@ -38,7 +37,6 @@ namespace mapcontrol
|
||||
|
||||
void TrailItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
// painter->drawRect(QRectF(-3,-3,6,6));
|
||||
painter->setBrush(m_brush);
|
||||
painter->drawEllipse(-2,-2,4,4);
|
||||
}
|
||||
@ -53,5 +51,8 @@ namespace mapcontrol
|
||||
return Type;
|
||||
}
|
||||
|
||||
|
||||
void TrailItem::setPosSLOT()
|
||||
{
|
||||
setPos(m_map->FromLatLngToLocal(this->coord).X(),m_map->FromLatLngToLocal(this->coord).Y());
|
||||
}
|
||||
}
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file trailitem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a WayPoint
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -32,6 +32,7 @@
|
||||
#include <QLabel>
|
||||
#include "../internals/pointlatlng.h"
|
||||
#include <QObject>
|
||||
#include "mapgraphicitem.h"
|
||||
|
||||
namespace mapcontrol
|
||||
{
|
||||
@ -42,7 +43,7 @@ namespace mapcontrol
|
||||
Q_INTERFACES(QGraphicsItem)
|
||||
public:
|
||||
enum { Type = UserType + 3 };
|
||||
TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, QGraphicsItem* parent);
|
||||
TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color,MapGraphicItem * map);
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget);
|
||||
QRectF boundingRect() const;
|
||||
@ -50,10 +51,9 @@ namespace mapcontrol
|
||||
internals::PointLatLng coord;
|
||||
private:
|
||||
QBrush m_brush;
|
||||
|
||||
|
||||
MapGraphicItem * m_map;
|
||||
public slots:
|
||||
|
||||
void setPosSLOT();
|
||||
signals:
|
||||
|
||||
};
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file trailitem.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A graphicsItem representing a trail point
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
@ -28,29 +28,21 @@
|
||||
|
||||
namespace mapcontrol
|
||||
{
|
||||
TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, QGraphicsItem* parent):QGraphicsLineItem(parent),coord1(coord1),coord2(coord2)
|
||||
TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, MapGraphicItem * map):QGraphicsLineItem(map),coord1(coord1),coord2(coord2),m_brush(color),m_map(map)
|
||||
{
|
||||
m_brush=color;
|
||||
QPen pen;
|
||||
pen.setBrush(m_brush);
|
||||
pen.setWidth(1);
|
||||
this->setPen(pen);
|
||||
}
|
||||
/*
|
||||
void TrailLineItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget)
|
||||
{
|
||||
// painter->drawRect(QRectF(-3,-3,6,6));
|
||||
painter->setBrush(m_brush);
|
||||
QPen pen;
|
||||
pen.setBrush(m_brush);
|
||||
pen.setWidth(2);
|
||||
painter->drawLine(this->line().x1(),this->line().y1(),this->line().x2(),this->line().y2());
|
||||
}
|
||||
*/
|
||||
|
||||
int TrailLineItem::type()const
|
||||
{
|
||||
return Type;
|
||||
}
|
||||
|
||||
|
||||
void TrailLineItem::setLineSlot()
|
||||
{
|
||||
setLine(m_map->FromLatLngToLocal(this->coord1).X(),m_map->FromLatLngToLocal(this->coord1).Y(),m_map->FromLatLngToLocal(this->coord2).X(),m_map->FromLatLngToLocal(this->coord2).Y());
|
||||
}
|
||||
}
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user