mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merge branch 'next' into corvuscorax/OP-1317_IMU_wind_estimation
This commit is contained in:
commit
205edac762
@ -90,5 +90,27 @@ void quat_inverse(float q[4]);
|
||||
void quat_copy(const float q[4], float qnew[4]);
|
||||
void quat_mult(const float q1[4], const float q2[4], float qout[4]);
|
||||
void rot_mult(float R[3][3], const float vec[3], float vec_out[3]);
|
||||
/**
|
||||
* matrix_mult_3x3f - perform a multiplication between two 3x3 float matrices
|
||||
* result = a*b
|
||||
* @param a
|
||||
* @param b
|
||||
* @param result
|
||||
*/
|
||||
inline void matrix_mult_3x3f(float a[3][3], float b[3][3], float result[3][3])
|
||||
{
|
||||
result[0][0] = a[0][0] * b[0][0] + a[1][0] * b[0][1] + a[2][0] * b[0][2];
|
||||
result[0][1] = a[0][1] * b[0][0] + a[1][1] * b[0][1] + a[2][1] * b[0][2];
|
||||
result[0][2] = a[0][2] * b[0][0] + a[1][2] * b[0][1] + a[2][2] * b[0][2];
|
||||
|
||||
result[1][0] = a[0][0] * b[1][0] + a[1][0] * b[1][1] + a[2][0] * b[1][2];
|
||||
result[1][1] = a[0][1] * b[1][0] + a[1][1] * b[1][1] + a[2][1] * b[1][2];
|
||||
result[1][2] = a[0][2] * b[1][0] + a[1][2] * b[1][1] + a[2][2] * b[1][2];
|
||||
|
||||
result[2][0] = a[0][0] * b[2][0] + a[1][0] * b[2][1] + a[2][0] * b[2][2];
|
||||
result[2][1] = a[0][1] * b[2][0] + a[1][1] * b[2][1] + a[2][1] * b[2][2];
|
||||
result[2][2] = a[0][2] * b[2][0] + a[1][2] * b[2][1] + a[2][2] * b[2][2];
|
||||
}
|
||||
|
||||
|
||||
#endif // COORDINATECONVERSIONS_H_
|
||||
|
94
flight/libraries/inc/plans.h
Normal file
94
flight/libraries/inc/plans.h
Normal file
@ -0,0 +1,94 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotLibraries OpenPilot Libraries
|
||||
* @{
|
||||
* @addtogroup Navigation
|
||||
* @brief setups RTH/PH and other pathfollower/pathplanner status
|
||||
* @{
|
||||
*
|
||||
* @file plan.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PLANS_H_
|
||||
#define PLANS_H_
|
||||
#include <pios_math.h>
|
||||
|
||||
/** \page standard Plans
|
||||
How to use this library
|
||||
\li Call plan_initialize() to init all needed struct and uavos at startup.<br>
|
||||
It may be safely called more than once.<br>
|
||||
|
||||
\li Functions called plan_setup_* needs to be called once, every time the requested function is engaged.<br>
|
||||
|
||||
\li Functions called plan_run_* are to be periodically called while the requested mode is engaged.<br>
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief initialize UAVOs and structs used by this library
|
||||
*/
|
||||
void plan_initialize();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for positionhold
|
||||
*/
|
||||
void plan_setup_positionHold();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for return to base
|
||||
*/
|
||||
void plan_setup_returnToBase();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for land
|
||||
*/
|
||||
void plan_setup_land();
|
||||
|
||||
/**
|
||||
* @brief execute land
|
||||
*/
|
||||
void plan_run_land();
|
||||
|
||||
/**
|
||||
* @brief setup pathfollower for positionvario
|
||||
*/
|
||||
void plan_setup_PositionVarioFPV();
|
||||
void plan_setup_PositionVarioLOS();
|
||||
void plan_setup_PositionVarioNSEW();
|
||||
|
||||
/**
|
||||
* @brief run for positionvario
|
||||
*/
|
||||
void plan_run_PositionVarioFPV();
|
||||
void plan_run_PositionVarioLOS();
|
||||
void plan_run_PositionVarioNSEW();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for AutoCruise
|
||||
*/
|
||||
void plan_setup_AutoCruise();
|
||||
|
||||
/**
|
||||
* @brief execute AutoCruise
|
||||
*/
|
||||
void plan_run_AutoCruise();
|
||||
|
||||
#endif /* PLANS_H_ */
|
465
flight/libraries/plans.c
Normal file
465
flight/libraries/plans.c
Normal file
@ -0,0 +1,465 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotLibraries OpenPilot Libraries
|
||||
* @{
|
||||
* @addtogroup Navigation
|
||||
* @brief setups RTH/PH and other pathfollower/pathplanner status
|
||||
* @{
|
||||
*
|
||||
* @file plan.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
******************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <plans.h>
|
||||
#include <openpilot.h>
|
||||
#include <attitudesettings.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <pathdesired.h>
|
||||
#include <positionstate.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <attitudestate.h>
|
||||
#include <sin_lookup.h>
|
||||
|
||||
#define UPDATE_EXPECTED 0.02f
|
||||
#define UPDATE_MIN 1.0e-6f
|
||||
#define UPDATE_MAX 1.0f
|
||||
#define UPDATE_ALPHA 1.0e-2f
|
||||
|
||||
/**
|
||||
* @brief initialize UAVOs and structs used by this library
|
||||
*/
|
||||
void plan_initialize()
|
||||
{
|
||||
TakeOffLocationInitialize();
|
||||
PositionStateInitialize();
|
||||
PathDesiredInitialize();
|
||||
FlightModeSettingsInitialize();
|
||||
AttitudeStateInitialize();
|
||||
ManualControlCommandInitialize();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for positionhold
|
||||
*/
|
||||
void plan_setup_positionHold()
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
float startingVelocity;
|
||||
FlightModeSettingsPositionHoldStartingVelocityGet(&startingVelocity);
|
||||
|
||||
pathDesired.End.North = positionState.North;
|
||||
pathDesired.End.East = positionState.East;
|
||||
pathDesired.End.Down = positionState.Down;
|
||||
pathDesired.Start.North = positionState.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = positionState.East;
|
||||
pathDesired.Start.Down = positionState.Down;
|
||||
pathDesired.StartingVelocity = startingVelocity;
|
||||
pathDesired.EndingVelocity = 0.0f;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for return to base
|
||||
*/
|
||||
void plan_setup_returnToBase()
|
||||
{
|
||||
// Simple Return To Base mode - keep altitude the same applying configured delta, fly to takeoff position
|
||||
float positionStateDown;
|
||||
|
||||
PositionStateDownGet(&positionStateDown);
|
||||
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
|
||||
TakeOffLocationData takeoffLocation;
|
||||
TakeOffLocationGet(&takeoffLocation);
|
||||
|
||||
// TODO: right now VTOLPF does fly straight to destination altitude.
|
||||
// For a safer RTB destination altitude will be the higher between takeofflocation and current position (corrected with safety margin)
|
||||
|
||||
float destDown;
|
||||
FlightModeSettingsReturnToBaseAltitudeOffsetGet(&destDown);
|
||||
destDown = MIN(positionStateDown, takeoffLocation.Down) - destDown;
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
float startingVelocity;
|
||||
FlightModeSettingsPositionHoldStartingVelocityGet(&startingVelocity);
|
||||
|
||||
pathDesired.End.North = takeoffLocation.North;
|
||||
pathDesired.End.East = takeoffLocation.East;
|
||||
pathDesired.End.Down = destDown;
|
||||
|
||||
pathDesired.Start.North = takeoffLocation.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = takeoffLocation.East;
|
||||
pathDesired.Start.Down = destDown;
|
||||
|
||||
pathDesired.StartingVelocity = startingVelocity;
|
||||
pathDesired.EndingVelocity = 0.0f;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
|
||||
void plan_setup_land()
|
||||
{
|
||||
plan_setup_positionHold();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief execute land
|
||||
*/
|
||||
void plan_run_land()
|
||||
{
|
||||
PathDesiredEndData pathDesiredEnd;
|
||||
|
||||
PathDesiredEndGet(&pathDesiredEnd);
|
||||
|
||||
PositionStateDownGet(&pathDesiredEnd.Down);
|
||||
pathDesiredEnd.Down += 5;
|
||||
|
||||
PathDesiredEndSet(&pathDesiredEnd);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief positionvario functionality
|
||||
*/
|
||||
static bool vario_hold = true;
|
||||
static float hold_position[3];
|
||||
|
||||
static void plan_setup_PositionVario()
|
||||
{
|
||||
vario_hold = true;
|
||||
plan_setup_positionHold();
|
||||
}
|
||||
|
||||
void plan_setup_PositionVarioFPV()
|
||||
{
|
||||
plan_setup_PositionVario();
|
||||
}
|
||||
|
||||
void plan_setup_PositionVarioLOS()
|
||||
{
|
||||
plan_setup_PositionVario();
|
||||
}
|
||||
|
||||
void plan_setup_PositionVarioNSEW()
|
||||
{
|
||||
plan_setup_PositionVario();
|
||||
}
|
||||
|
||||
|
||||
#define DEADBAND 0.1f
|
||||
static bool normalizeDeadband(float controlVector[4])
|
||||
{
|
||||
bool moving = false;
|
||||
|
||||
// roll, pitch, yaw between -1 and +1
|
||||
// thrust between 0 and 1 mapped to -1 to +1
|
||||
controlVector[3] = (2.0f * controlVector[3]) - 1.0f;
|
||||
int t;
|
||||
|
||||
for (t = 0; t < 4; t++) {
|
||||
if (controlVector[t] < -DEADBAND) {
|
||||
moving = true;
|
||||
controlVector[t] += DEADBAND;
|
||||
} else if (controlVector[t] > DEADBAND) {
|
||||
moving = true;
|
||||
controlVector[t] -= DEADBAND;
|
||||
} else {
|
||||
controlVector[t] = 0.0f;
|
||||
}
|
||||
// deadband has been cut out, scale value back to [-1,+1]
|
||||
controlVector[t] *= (1.0f / (1.0f - DEADBAND));
|
||||
controlVector[t] = boundf(controlVector[t], -1.0f, 1.0f);
|
||||
}
|
||||
|
||||
return moving;
|
||||
}
|
||||
|
||||
typedef enum { FPV, LOS, NSEW } vario_type;
|
||||
|
||||
static void getVector(float controlVector[4], vario_type type)
|
||||
{
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
|
||||
// scale controlVector[3] (thrust) by vertical/horizontal to have vertical plane less sensitive
|
||||
controlVector[3] *= offset.Vertical / offset.Horizontal;
|
||||
|
||||
float length = sqrtf(controlVector[0] * controlVector[0] + controlVector[1] * controlVector[1] + controlVector[3] * controlVector[3]);
|
||||
|
||||
if (length <= 1e-9f) {
|
||||
length = 1.0f; // should never happen as getVector is not called if control within deadband
|
||||
}
|
||||
{
|
||||
float direction[3] = {
|
||||
controlVector[1] / length, // pitch is north
|
||||
controlVector[0] / length, // roll is east
|
||||
controlVector[3] / length // thrust is down
|
||||
};
|
||||
controlVector[0] = direction[0];
|
||||
controlVector[1] = direction[1];
|
||||
controlVector[2] = direction[2];
|
||||
}
|
||||
controlVector[3] = length * offset.Horizontal;
|
||||
|
||||
// rotate north and east - rotation angle based on type
|
||||
float angle;
|
||||
switch (type) {
|
||||
case NSEW:
|
||||
angle = 0.0f;
|
||||
// NSEW no rotation takes place
|
||||
break;
|
||||
case FPV:
|
||||
// local rotation, using current yaw
|
||||
AttitudeStateYawGet(&angle);
|
||||
break;
|
||||
case LOS:
|
||||
// determine location based on vector from takeoff to current location
|
||||
{
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
TakeOffLocationData takeoffLocation;
|
||||
TakeOffLocationGet(&takeoffLocation);
|
||||
angle = RAD2DEG(atan2f(positionState.East - takeoffLocation.East, positionState.North - takeoffLocation.North));
|
||||
}
|
||||
break;
|
||||
}
|
||||
// rotate horizontally by angle
|
||||
{
|
||||
float rotated[2] = {
|
||||
controlVector[0] * cos_lookup_deg(angle) - controlVector[1] * sin_lookup_deg(angle),
|
||||
controlVector[0] * sin_lookup_deg(angle) + controlVector[1] * cos_lookup_deg(angle)
|
||||
};
|
||||
controlVector[0] = rotated[0];
|
||||
controlVector[1] = rotated[1];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void plan_run_PositionVario(vario_type type)
|
||||
{
|
||||
float controlVector[4];
|
||||
PathDesiredData pathDesired;
|
||||
|
||||
PathDesiredGet(&pathDesired);
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
|
||||
|
||||
ManualControlCommandRollGet(&controlVector[0]);
|
||||
ManualControlCommandPitchGet(&controlVector[1]);
|
||||
ManualControlCommandYawGet(&controlVector[2]);
|
||||
ManualControlCommandThrustGet(&controlVector[3]);
|
||||
|
||||
// check if movement is desired
|
||||
if (normalizeDeadband(controlVector) == false) {
|
||||
// no movement desired, re-enter positionHold at current start-position
|
||||
if (!vario_hold) {
|
||||
vario_hold = true;
|
||||
|
||||
// new hold position is the position that was previously the start position
|
||||
pathDesired.End.North = hold_position[0];
|
||||
pathDesired.End.East = hold_position[1];
|
||||
pathDesired.End.Down = hold_position[2];
|
||||
// while the new start position has the same offset as in position hold
|
||||
pathDesired.Start.North = pathDesired.End.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = pathDesired.End.East;
|
||||
pathDesired.Start.Down = pathDesired.End.Down;
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
} else {
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
|
||||
// flip pitch to have pitch down (away) point north
|
||||
controlVector[1] = -controlVector[1];
|
||||
getVector(controlVector, type);
|
||||
|
||||
// layout of control Vector : unitVector in movement direction {0,1,2} vector length {3} velocity {4}
|
||||
if (vario_hold) {
|
||||
// start position is the position that was previously the hold position
|
||||
vario_hold = false;
|
||||
hold_position[0] = pathDesired.End.North;
|
||||
hold_position[1] = pathDesired.End.East;
|
||||
hold_position[2] = pathDesired.End.Down;
|
||||
} else {
|
||||
// start position is advanced according to movement - in the direction of ControlVector only
|
||||
// projection using scalar product
|
||||
float kp = (positionState.North - hold_position[0]) * controlVector[0]
|
||||
+ (positionState.East - hold_position[1]) * controlVector[1]
|
||||
+ (positionState.Down - hold_position[2]) * -controlVector[2];
|
||||
if (kp > 0.0f) {
|
||||
hold_position[0] += kp * controlVector[0];
|
||||
hold_position[1] += kp * controlVector[1];
|
||||
hold_position[2] += kp * -controlVector[2];
|
||||
}
|
||||
}
|
||||
// new destination position is advanced based on controlVector
|
||||
pathDesired.End.North = hold_position[0] + controlVector[0] * controlVector[3];
|
||||
pathDesired.End.East = hold_position[1] + controlVector[1] * controlVector[3];
|
||||
pathDesired.End.Down = hold_position[2] - controlVector[2] * controlVector[3];
|
||||
// the new start position has the same offset as in position hold
|
||||
pathDesired.Start.North = pathDesired.End.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = pathDesired.End.East;
|
||||
pathDesired.Start.Down = pathDesired.End.Down;
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
}
|
||||
void plan_run_PositionVarioFPV()
|
||||
{
|
||||
plan_run_PositionVario(FPV);
|
||||
}
|
||||
|
||||
void plan_run_PositionVarioLOS()
|
||||
{
|
||||
plan_run_PositionVario(LOS);
|
||||
}
|
||||
|
||||
void plan_run_PositionVarioNSEW()
|
||||
{
|
||||
plan_run_PositionVario(NSEW);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for AutoCruise
|
||||
*/
|
||||
static PiOSDeltatimeConfig actimeval;
|
||||
void plan_setup_AutoCruise()
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
float startingVelocity;
|
||||
FlightModeSettingsPositionHoldStartingVelocityGet(&startingVelocity);
|
||||
|
||||
// initialization is flight in direction of the nose.
|
||||
// the velocity is not relevant, as it will be reset by the run function even during first call
|
||||
float angle;
|
||||
AttitudeStateYawGet(&angle);
|
||||
float vector[2] = {
|
||||
cos_lookup_deg(angle),
|
||||
sin_lookup_deg(angle)
|
||||
};
|
||||
hold_position[0] = positionState.North;
|
||||
hold_position[1] = positionState.East;
|
||||
hold_position[2] = positionState.Down;
|
||||
pathDesired.End.North = hold_position[0] + vector[0];
|
||||
pathDesired.End.East = hold_position[1] + vector[1];
|
||||
pathDesired.End.Down = hold_position[2];
|
||||
// start position has the same offset as in position hold
|
||||
pathDesired.Start.North = pathDesired.End.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = pathDesired.End.East;
|
||||
pathDesired.Start.Down = pathDesired.End.Down;
|
||||
pathDesired.StartingVelocity = startingVelocity;
|
||||
pathDesired.EndingVelocity = 0.0f;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
|
||||
PathDesiredSet(&pathDesired);
|
||||
|
||||
// re-iniztializing deltatime is valid and also good practice here since
|
||||
// getAverageSeconds() has not been called/updated in a long time if we were in a different flightmode.
|
||||
PIOS_DELTATIME_Init(&actimeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief execute autocruise
|
||||
*/
|
||||
void plan_run_AutoCruise()
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
FlightModeSettingsPositionHoldOffsetData offset;
|
||||
FlightModeSettingsPositionHoldOffsetGet(&offset);
|
||||
|
||||
float controlVector[4];
|
||||
ManualControlCommandRollGet(&controlVector[0]);
|
||||
ManualControlCommandPitchGet(&controlVector[1]);
|
||||
ManualControlCommandYawGet(&controlVector[2]);
|
||||
controlVector[3] = 0.5f; // dummy, thrust is normalized separately
|
||||
normalizeDeadband(controlVector); // return value ignored
|
||||
ManualControlCommandThrustGet(&controlVector[3]); // no deadband as we are using thrust for velocity
|
||||
controlVector[3] = boundf(controlVector[3], 1e-6f, 1.0f); // bound to above zero, to prevent loss of vector direction
|
||||
|
||||
// normalize old desired movement vector
|
||||
float vector[3] = { pathDesired.End.North - hold_position[0],
|
||||
pathDesired.End.East - hold_position[1],
|
||||
pathDesired.End.Down - hold_position[2] };
|
||||
float length = sqrtf(vector[0] * vector[0] + vector[1] * vector[1] + vector[2] * vector[2]);
|
||||
if (length < 1e-9f) {
|
||||
length = 1.0f; // should not happen since initialized properly in setup()
|
||||
}
|
||||
vector[0] /= length;
|
||||
vector[1] /= length;
|
||||
vector[2] /= length;
|
||||
|
||||
// start position is advanced according to actual movement - in the direction of desired vector only
|
||||
// projection using scalar product
|
||||
float kp = (positionState.North - hold_position[0]) * vector[0]
|
||||
+ (positionState.East - hold_position[1]) * vector[1]
|
||||
+ (positionState.Down - hold_position[2]) * vector[2];
|
||||
if (kp > 0.0f) {
|
||||
hold_position[0] += kp * vector[0];
|
||||
hold_position[1] += kp * vector[1];
|
||||
hold_position[2] += kp * vector[2];
|
||||
}
|
||||
|
||||
// new angle is equal to old angle plus offset depending on yaw input and time
|
||||
// (controlVector is normalized with a deadband, change is zero within deadband)
|
||||
float angle = RAD2DEG(atan2f(vector[1], vector[0]));
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&actimeval);
|
||||
angle += 10.0f * controlVector[2] * dT; // TODO magic value could eventually end up in a to be created settings
|
||||
|
||||
// resulting movement vector is scaled by velocity demand in controlvector[3] [0.0-1.0]
|
||||
vector[0] = cosf(DEG2RAD(angle)) * offset.Horizontal * controlVector[3];
|
||||
vector[1] = sinf(DEG2RAD(angle)) * offset.Horizontal * controlVector[3];
|
||||
vector[2] = -controlVector[1] * offset.Vertical * controlVector[3];
|
||||
|
||||
pathDesired.End.North = hold_position[0] + vector[0];
|
||||
pathDesired.End.East = hold_position[1] + vector[1];
|
||||
pathDesired.End.Down = hold_position[2] + vector[2];
|
||||
// start position has the same offset as in position hold
|
||||
pathDesired.Start.North = pathDesired.End.North + offset.Horizontal; // in FlyEndPoint the direction of this vector does not matter
|
||||
pathDesired.Start.East = pathDesired.End.East;
|
||||
pathDesired.Start.Down = pathDesired.End.Down;
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
@ -37,8 +37,13 @@
|
||||
#include <flightmodesettings.h>
|
||||
#include <systemsettings.h>
|
||||
#include <systemalarms.h>
|
||||
#include <revosettings.h>
|
||||
#include <taskinfo.h>
|
||||
|
||||
// a number of useful macros
|
||||
#define ADDSEVERITY(check) severity = (severity != SYSTEMALARMS_ALARM_OK ? severity : ((check) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_ERROR))
|
||||
|
||||
|
||||
/****************************
|
||||
* Current checks:
|
||||
* 1. If a flight mode switch allows autotune and autotune module not running
|
||||
@ -46,7 +51,7 @@
|
||||
****************************/
|
||||
|
||||
// ! Check a stabilization mode switch position for safety
|
||||
static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol);
|
||||
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol);
|
||||
|
||||
/**
|
||||
* Run a preflight check over the hardware configuration
|
||||
@ -61,8 +66,27 @@ int32_t configuration_check()
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
bool coptercontrol = bdinfo->board_type == 0x04;
|
||||
|
||||
// Classify navigation capability
|
||||
#ifdef REVOLUTION
|
||||
RevoSettingsInitialize();
|
||||
uint8_t revoFusion;
|
||||
RevoSettingsFusionAlgorithmGet(&revoFusion);
|
||||
bool navCapableFusion;
|
||||
switch (revoFusion) {
|
||||
case REVOSETTINGS_FUSIONALGORITHM_COMPLEMENTARYMAGGPSOUTDOOR:
|
||||
case REVOSETTINGS_FUSIONALGORITHM_INS13GPSOUTDOOR:
|
||||
navCapableFusion = true;
|
||||
break;
|
||||
default:
|
||||
navCapableFusion = false;
|
||||
}
|
||||
#else
|
||||
const bool navCapableFusion = false;
|
||||
#endif
|
||||
|
||||
|
||||
// Classify airframe type
|
||||
bool multirotor = true;
|
||||
bool multirotor;
|
||||
uint8_t airframe_type;
|
||||
|
||||
SystemSettingsAirframeTypeGet(&airframe_type);
|
||||
@ -93,82 +117,54 @@ int32_t configuration_check()
|
||||
for (uint32_t i = 0; i < num_modes; i++) {
|
||||
switch (modes[i]) {
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_MANUAL:
|
||||
if (multirotor) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
ADDSEVERITY(!multirotor);
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(1, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(2, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(3, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED4:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(4, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(4, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED5:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(5, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(5, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED6:
|
||||
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(6, multirotor, coptercontrol) : severity;
|
||||
ADDSEVERITY(check_stabilization_settings(6, multirotor, coptercontrol));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTUNE:
|
||||
if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_AUTOTUNE)) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
||||
if (coptercontrol) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
} else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) {
|
||||
// Revo supports Position Hold
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_LAND:
|
||||
if (coptercontrol) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
} else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) {
|
||||
// Revo supports AutoLand Mode
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POI:
|
||||
if (coptercontrol) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
} else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) {
|
||||
// Revo supports POI Mode
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
ADDSEVERITY(PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_AUTOTUNE));
|
||||
break;
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_PATHPLANNER:
|
||||
if (coptercontrol) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
} else {
|
||||
// Revo supports PathPlanner and that must be OK or we are not sane
|
||||
// PathPlan alarm is uninitialized if not running
|
||||
// PathPlan alarm is warning or error if the flightplan is invalid
|
||||
SystemAlarmsAlarmData alarms;
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
if (alarms.PathPlan != SYSTEMALARMS_ALARM_OK) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
}
|
||||
break;
|
||||
{
|
||||
// Revo supports PathPlanner and that must be OK or we are not sane
|
||||
// PathPlan alarm is uninitialized if not running
|
||||
// PathPlan alarm is warning or error if the flightplan is invalid
|
||||
SystemAlarmsAlarmData alarms;
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
ADDSEVERITY(alarms.PathPlan == SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
// intentionally no break as this also needs pathfollower
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONVARIOFPV:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONVARIOLOS:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONVARIONSEW:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_LAND:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POI:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE:
|
||||
if (coptercontrol) {
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
} else if (!PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER)) {
|
||||
// Revo supports ReturnToBase
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
}
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOCRUISE:
|
||||
ADDSEVERITY(!coptercontrol);
|
||||
ADDSEVERITY(PIOS_TASK_MONITOR_IsRunning(TASKINFO_RUNNING_PATHFOLLOWER));
|
||||
ADDSEVERITY(navCapableFusion);
|
||||
break;
|
||||
default:
|
||||
// Uncovered modes are automatically an error
|
||||
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||
ADDSEVERITY(false);
|
||||
}
|
||||
// mark the first encountered erroneous setting in status and substatus
|
||||
if ((severity != SYSTEMALARMS_ALARM_OK) && (alarmstatus == SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE)) {
|
||||
@ -191,9 +187,9 @@ int32_t configuration_check()
|
||||
* Checks the stabiliation settings for a paritcular mode and makes
|
||||
* sure it is appropriate for the airframe
|
||||
* @param[in] index Which stabilization mode to check
|
||||
* @returns SYSTEMALARMS_ALARM_OK or SYSTEMALARMS_ALARM_ERROR
|
||||
* @returns true or false
|
||||
*/
|
||||
static int32_t check_stabilization_settings(int index, bool multirotor, bool coptercontrol)
|
||||
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol)
|
||||
{
|
||||
uint8_t modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM];
|
||||
|
||||
@ -218,7 +214,7 @@ static int32_t check_stabilization_settings(int index, bool multirotor, bool cop
|
||||
FlightModeSettingsStabilization6SettingsArrayGet(modes);
|
||||
break;
|
||||
default:
|
||||
return SYSTEMALARMS_ALARM_ERROR;
|
||||
return false;
|
||||
}
|
||||
|
||||
// For multirotors verify that roll/pitch/yaw are not set to "none"
|
||||
@ -226,7 +222,7 @@ static int32_t check_stabilization_settings(int index, bool multirotor, bool cop
|
||||
if (multirotor) {
|
||||
for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
|
||||
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL) {
|
||||
return SYSTEMALARMS_ALARM_ERROR;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -234,26 +230,26 @@ static int32_t check_stabilization_settings(int index, bool multirotor, bool cop
|
||||
// coptercontrol cannot do altitude holding
|
||||
if (coptercontrol) {
|
||||
if (modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO
|
||||
) {
|
||||
return SYSTEMALARMS_ALARM_ERROR;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// check that thrust modes are only set to thrust axis
|
||||
for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST; i++) {
|
||||
if (modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|
||||
|| modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
|
||||
|| modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO
|
||||
) {
|
||||
return SYSTEMALARMS_ALARM_ERROR;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
if (!(modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO
|
||||
|| modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL
|
||||
)) {
|
||||
return SYSTEMALARMS_ALARM_ERROR;
|
||||
return false;
|
||||
}
|
||||
|
||||
// Warning: This assumes that certain conditions in the XML file are met. That
|
||||
@ -261,5 +257,5 @@ static int32_t check_stabilization_settings(int index, bool multirotor, bool cop
|
||||
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL
|
||||
// (this is checked at compile time by static constraint manualcontrol.h)
|
||||
|
||||
return SYSTEMALARMS_ALARM_OK;
|
||||
return true;
|
||||
}
|
||||
|
@ -63,6 +63,7 @@
|
||||
#include "taskinfo.h"
|
||||
#include <pios_struct_helper.h>
|
||||
|
||||
#include "sin_lookup.h"
|
||||
#include "paths.h"
|
||||
#include "CoordinateConversions.h"
|
||||
|
||||
@ -85,6 +86,7 @@ static void updatePathVelocity();
|
||||
static uint8_t updateFixedDesiredAttitude();
|
||||
static void updateFixedAttitude();
|
||||
static void airspeedStateUpdatedCb(UAVObjEvent *ev);
|
||||
static bool correctCourse(float *C, float *V, float *F, float s);
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
@ -125,17 +127,17 @@ int32_t FixedWingPathFollowerInitialize()
|
||||
}
|
||||
MODULE_INITCALL(FixedWingPathFollowerInitialize, FixedWingPathFollowerStart);
|
||||
|
||||
static float northVelIntegral = 0;
|
||||
static float eastVelIntegral = 0;
|
||||
static float downVelIntegral = 0;
|
||||
static float northVelIntegral = 0.0f;
|
||||
static float eastVelIntegral = 0.0f;
|
||||
static float downVelIntegral = 0.0f;
|
||||
|
||||
static float courseIntegral = 0;
|
||||
static float speedIntegral = 0;
|
||||
static float powerIntegral = 0;
|
||||
static float airspeedErrorInt = 0;
|
||||
static float courseIntegral = 0.0f;
|
||||
static float speedIntegral = 0.0f;
|
||||
static float powerIntegral = 0.0f;
|
||||
static float airspeedErrorInt = 0.0f;
|
||||
|
||||
// correct speed by measured airspeed
|
||||
static float indicatedAirspeedStateBias = 0;
|
||||
static float indicatedAirspeedStateBias = 0.0f;
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
@ -225,12 +227,12 @@ static void pathfollowerTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
} else {
|
||||
// Be cleaner and get rid of global variables
|
||||
northVelIntegral = 0;
|
||||
eastVelIntegral = 0;
|
||||
downVelIntegral = 0;
|
||||
courseIntegral = 0;
|
||||
speedIntegral = 0;
|
||||
powerIntegral = 0;
|
||||
northVelIntegral = 0.0f;
|
||||
eastVelIntegral = 0.0f;
|
||||
downVelIntegral = 0.0f;
|
||||
courseIntegral = 0.0f;
|
||||
speedIntegral = 0.0f;
|
||||
powerIntegral = 0.0f;
|
||||
}
|
||||
PathStatusSet(&pathStatus);
|
||||
}
|
||||
@ -276,14 +278,14 @@ static void updatePathVelocity()
|
||||
case PATHDESIRED_MODE_DRIVEVECTOR:
|
||||
default:
|
||||
groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) *
|
||||
boundf(progress.fractional_progress, 0, 1);
|
||||
boundf(progress.fractional_progress, 0.0f, 1.0f);
|
||||
altitudeSetpoint = pathDesired.Start.Down + (pathDesired.End.Down - pathDesired.Start.Down) *
|
||||
boundf(progress.fractional_progress, 0, 1);
|
||||
boundf(progress.fractional_progress, 0.0f, 1.0f);
|
||||
break;
|
||||
}
|
||||
// make sure groundspeed is not zero
|
||||
if (groundspeed < 1e-2f) {
|
||||
groundspeed = 1e-2f;
|
||||
if (groundspeed < 1e-6f) {
|
||||
groundspeed = 1e-6f;
|
||||
}
|
||||
|
||||
// calculate velocity - can be zero if waypoints are too close
|
||||
@ -302,24 +304,12 @@ static void updatePathVelocity()
|
||||
// in this case the plane effectively needs to be turned around
|
||||
// indicators:
|
||||
// difference between correction_direction and velocitystate >90 degrees and
|
||||
// difference between path_direction and velocitystate >90 degrees ( 4th sector, facing away from eerything )
|
||||
// difference between path_direction and velocitystate >90 degrees ( 4th sector, facing away from everything )
|
||||
// fix: ignore correction, steer in path direction until the situation has become better (condition doesn't apply anymore)
|
||||
float angle1 = RAD2DEG(atan2f(progress.path_direction[1], progress.path_direction[0]) - atan2f(velocityState.East, velocityState.North));
|
||||
float angle2 = RAD2DEG(atan2f(progress.correction_direction[1], progress.correction_direction[0]) - atan2f(velocityState.East, velocityState.North));
|
||||
if (angle1 < -180.0f) {
|
||||
angle1 += 360.0f;
|
||||
}
|
||||
if (angle1 > 180.0f) {
|
||||
angle1 -= 360.0f;
|
||||
}
|
||||
if (angle2 < -180.0f) {
|
||||
angle2 += 360.0f;
|
||||
}
|
||||
if (angle2 > 180.0f) {
|
||||
angle2 -= 360.0f;
|
||||
}
|
||||
if (fabsf(angle1) >= 90.0f && fabsf(angle2) >= 90.0f) {
|
||||
error_speed = 0;
|
||||
if ( // calculating angles < 90 degrees through dot products
|
||||
((progress.path_direction[0] * velocityState.North + progress.path_direction[1] * velocityState.East) < 0.0f) &&
|
||||
((progress.correction_direction[0] * velocityState.North + progress.correction_direction[1] * velocityState.East) < 0.0f)) {
|
||||
error_speed = 0.0f;
|
||||
}
|
||||
|
||||
// calculate correction - can also be zero if correction vector is 0 or no error present
|
||||
@ -328,14 +318,16 @@ static void updatePathVelocity()
|
||||
|
||||
// scale to correct length
|
||||
float l = sqrtf(velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East);
|
||||
velocityDesired.North *= groundspeed / l;
|
||||
velocityDesired.East *= groundspeed / l;
|
||||
if (l > 1e-9f) {
|
||||
velocityDesired.North *= groundspeed / l;
|
||||
velocityDesired.East *= groundspeed / l;
|
||||
}
|
||||
|
||||
float downError = altitudeSetpoint - positionState.Down;
|
||||
velocityDesired.Down = downError * fixedwingpathfollowerSettings.VerticalPosP;
|
||||
velocityDesired.Down = downError * fixedwingpathfollowerSettings.VerticalPosP;
|
||||
|
||||
// update pathstatus
|
||||
pathStatus.error = progress.error;
|
||||
pathStatus.error = progress.error;
|
||||
pathStatus.fractional_progress = progress.fractional_progress;
|
||||
|
||||
VelocityDesiredSet(&velocityDesired);
|
||||
@ -384,8 +376,7 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
AirspeedStateData airspeedState;
|
||||
SystemSettingsData systemSettings;
|
||||
|
||||
float groundspeedState;
|
||||
float groundspeedDesired;
|
||||
float groundspeedProjection;
|
||||
float indicatedAirspeedState;
|
||||
float indicatedAirspeedDesired;
|
||||
float airspeedError;
|
||||
@ -396,10 +387,9 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
float descentspeedError;
|
||||
float powerCommand;
|
||||
|
||||
float bearing;
|
||||
float heading;
|
||||
float headingError;
|
||||
float course;
|
||||
float airspeedVector[2];
|
||||
float fluidMovement[2];
|
||||
float courseComponent[2];
|
||||
float courseError;
|
||||
float courseCommand;
|
||||
|
||||
@ -413,24 +403,54 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
AirspeedStateGet(&airspeedState);
|
||||
SystemSettingsGet(&systemSettings);
|
||||
|
||||
|
||||
/**
|
||||
* Compute speed error (required for thrust and pitch)
|
||||
* Compute speed error and course
|
||||
*/
|
||||
// missing sensors for airspeed-direction we have to assume within
|
||||
// reasonable error that measured airspeed is actually the airspeed
|
||||
// component in forward pointing direction
|
||||
// airspeedVector is normalized
|
||||
airspeedVector[0] = cos_lookup_deg(attitudeState.Yaw);
|
||||
airspeedVector[1] = sin_lookup_deg(attitudeState.Yaw);
|
||||
|
||||
// Current ground speed
|
||||
groundspeedState = sqrtf(velocityState.East * velocityState.East + velocityState.North * velocityState.North);
|
||||
// note that airspeedStateBias is ( calibratedAirspeed - groundSpeed ) at the time of measurement,
|
||||
// but thanks to accelerometers, groundspeed reacts faster to changes in direction
|
||||
// current ground speed projected in forward direction
|
||||
groundspeedProjection = velocityState.North * airspeedVector[0] + velocityState.East * airspeedVector[1];
|
||||
|
||||
// note that airspeedStateBias is ( calibratedAirspeed - groundspeedProjection ) at the time of measurement,
|
||||
// but thanks to accelerometers, groundspeedProjection reacts faster to changes in direction
|
||||
// than airspeed and gps sensors alone
|
||||
indicatedAirspeedState = groundspeedState + indicatedAirspeedStateBias;
|
||||
indicatedAirspeedState = groundspeedProjection + indicatedAirspeedStateBias;
|
||||
|
||||
// Desired ground speed
|
||||
groundspeedDesired = sqrtf(velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East);
|
||||
indicatedAirspeedDesired = boundf(groundspeedDesired + indicatedAirspeedStateBias,
|
||||
// fluidMovement is a vector describing the aproximate movement vector of
|
||||
// the surrounding fluid in 2d space (aka wind vector)
|
||||
fluidMovement[0] = velocityState.North - (indicatedAirspeedState * airspeedVector[0]);
|
||||
fluidMovement[1] = velocityState.East - (indicatedAirspeedState * airspeedVector[1]);
|
||||
|
||||
// calculate the movement vector we need to fly to reach velocityDesired -
|
||||
// taking fluidMovement into account
|
||||
courseComponent[0] = velocityDesired.North - fluidMovement[0];
|
||||
courseComponent[1] = velocityDesired.East - fluidMovement[1];
|
||||
|
||||
indicatedAirspeedDesired = boundf(sqrtf(courseComponent[0] * courseComponent[0] + courseComponent[1] * courseComponent[1]),
|
||||
fixedwingpathfollowerSettings.HorizontalVelMin,
|
||||
fixedwingpathfollowerSettings.HorizontalVelMax);
|
||||
|
||||
// if we could fly at arbitrary speeds, we'd just have to move towards the
|
||||
// courseComponent vector as previously calculated and we'd be fine
|
||||
// unfortunately however we are bound by min and max air speed limits, so
|
||||
// we need to recalculate the correct course to meet at least the
|
||||
// velocityDesired vector direction at our current speed
|
||||
// this overwrites courseComponent
|
||||
bool valid = correctCourse(courseComponent, (float *)&velocityDesired.North, fluidMovement, indicatedAirspeedDesired);
|
||||
|
||||
// Error condition: wind speed too high, we can't go where we want anymore
|
||||
fixedwingpathfollowerStatus.Errors.Wind = 0;
|
||||
if ((!valid) &&
|
||||
fixedwingpathfollowerSettings.Safetymargins.Wind > 0.5f) { // alarm switched on
|
||||
fixedwingpathfollowerStatus.Errors.Wind = 1;
|
||||
result = 0;
|
||||
}
|
||||
|
||||
// Airspeed error
|
||||
airspeedError = indicatedAirspeedDesired - indicatedAirspeedState;
|
||||
|
||||
@ -461,23 +481,18 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
result = 0;
|
||||
}
|
||||
|
||||
if (indicatedAirspeedState < 1e-6f) {
|
||||
// prevent division by zero, abort without controlling anything. This guidance mode is not suited for takeoff or touchdown, or handling stationary planes
|
||||
// also we cannot handle planes flying backwards, lets just wait until the nose drops
|
||||
fixedwingpathfollowerStatus.Errors.Lowspeed = 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Compute desired thrust command
|
||||
*/
|
||||
// compute saturated integral error thrust response. Make integral leaky for better performance. Approximately 30s time constant.
|
||||
if (fixedwingpathfollowerSettings.PowerPI.Ki > 0) {
|
||||
if (fixedwingpathfollowerSettings.PowerPI.Ki > 0.0f) {
|
||||
powerIntegral = boundf(powerIntegral + -descentspeedError * dT,
|
||||
-fixedwingpathfollowerSettings.PowerPI.ILimit / fixedwingpathfollowerSettings.PowerPI.Ki,
|
||||
fixedwingpathfollowerSettings.PowerPI.ILimit / fixedwingpathfollowerSettings.PowerPI.Ki
|
||||
) * (1.0f - 1.0f / (1.0f + 30.0f / dT));
|
||||
} else { powerIntegral = 0; }
|
||||
} else {
|
||||
powerIntegral = 0.0f;
|
||||
}
|
||||
|
||||
// Compute the cross feed from vertical speed to pitch, with saturation
|
||||
float speedErrorToPowerCommandComponent = boundf(
|
||||
@ -504,9 +519,9 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
// Error condition: plane cannot hold altitude at current speed.
|
||||
fixedwingpathfollowerStatus.Errors.Lowpower = 0;
|
||||
if (fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand >= fixedwingpathfollowerSettings.ThrustLimit.Max && // thrust at maximum
|
||||
velocityState.Down > 0 && // we ARE going down
|
||||
descentspeedDesired < 0 && // we WANT to go up
|
||||
airspeedError > 0 && // we are too slow already
|
||||
velocityState.Down > 0.0f && // we ARE going down
|
||||
descentspeedDesired < 0.0f && // we WANT to go up
|
||||
airspeedError > 0.0f && // we are too slow already
|
||||
fixedwingpathfollowerSettings.Safetymargins.Lowpower > 0.5f) { // alarm switched on
|
||||
fixedwingpathfollowerStatus.Errors.Lowpower = 1;
|
||||
result = 0;
|
||||
@ -514,9 +529,9 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
// Error condition: plane keeps climbing despite minimum thrust (opposite of above)
|
||||
fixedwingpathfollowerStatus.Errors.Highpower = 0;
|
||||
if (fixedwingpathfollowerSettings.ThrustLimit.Neutral + powerCommand <= fixedwingpathfollowerSettings.ThrustLimit.Min && // thrust at minimum
|
||||
velocityState.Down < 0 && // we ARE going up
|
||||
descentspeedDesired > 0 && // we WANT to go down
|
||||
airspeedError < 0 && // we are too fast already
|
||||
velocityState.Down < 0.0f && // we ARE going up
|
||||
descentspeedDesired > 0.0f && // we WANT to go down
|
||||
airspeedError < 0.0f && // we are too fast already
|
||||
fixedwingpathfollowerSettings.Safetymargins.Highpower > 0.5f) { // alarm switched on
|
||||
fixedwingpathfollowerStatus.Errors.Highpower = 1;
|
||||
result = 0;
|
||||
@ -526,7 +541,6 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
/**
|
||||
* Compute desired pitch command
|
||||
*/
|
||||
|
||||
if (fixedwingpathfollowerSettings.SpeedPI.Ki > 0) {
|
||||
// Integrate with saturation
|
||||
airspeedErrorInt = boundf(airspeedErrorInt + airspeedError * dT,
|
||||
@ -556,48 +570,18 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
// Error condition: high speed dive
|
||||
fixedwingpathfollowerStatus.Errors.Pitchcontrol = 0;
|
||||
if (fixedwingpathfollowerSettings.PitchLimit.Neutral + pitchCommand >= fixedwingpathfollowerSettings.PitchLimit.Max && // pitch demand is full up
|
||||
velocityState.Down > 0 && // we ARE going down
|
||||
descentspeedDesired < 0 && // we WANT to go up
|
||||
airspeedError < 0 && // we are too fast already
|
||||
velocityState.Down > 0.0f && // we ARE going down
|
||||
descentspeedDesired < 0.0f && // we WANT to go up
|
||||
airspeedError < 0.0f && // we are too fast already
|
||||
fixedwingpathfollowerSettings.Safetymargins.Pitchcontrol > 0.5f) { // alarm switched on
|
||||
fixedwingpathfollowerStatus.Errors.Pitchcontrol = 1;
|
||||
result = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculate where we are heading and why (wind issues)
|
||||
*/
|
||||
bearing = attitudeState.Yaw;
|
||||
heading = RAD2DEG(atan2f(velocityState.East, velocityState.North));
|
||||
headingError = heading - bearing;
|
||||
if (headingError < -180.0f) {
|
||||
headingError += 360.0f;
|
||||
}
|
||||
if (headingError > 180.0f) {
|
||||
headingError -= 360.0f;
|
||||
}
|
||||
// Error condition: wind speed is higher than airspeed. We are forced backwards!
|
||||
fixedwingpathfollowerStatus.Errors.Wind = 0;
|
||||
if ((headingError > fixedwingpathfollowerSettings.Safetymargins.Wind ||
|
||||
headingError < -fixedwingpathfollowerSettings.Safetymargins.Wind) &&
|
||||
fixedwingpathfollowerSettings.Safetymargins.Highpower > 0.5f) { // alarm switched on
|
||||
// we are flying backwards
|
||||
fixedwingpathfollowerStatus.Errors.Wind = 1;
|
||||
result = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Compute desired roll command
|
||||
*/
|
||||
if (groundspeedDesired > 1e-6f) {
|
||||
course = RAD2DEG(atan2f(velocityDesired.East, velocityDesired.North));
|
||||
|
||||
courseError = course - heading;
|
||||
} else {
|
||||
// if we are not supposed to move, run in a circle
|
||||
courseError = -90.0f;
|
||||
result = 0;
|
||||
}
|
||||
courseError = RAD2DEG(atan2f(courseComponent[1], courseComponent[0])) - attitudeState.Yaw;
|
||||
|
||||
if (courseError < -180.0f) {
|
||||
courseError += 360.0f;
|
||||
@ -606,6 +590,19 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
courseError -= 360.0f;
|
||||
}
|
||||
|
||||
// overlap calculation. Theres a dead zone behind the craft where the
|
||||
// counter-yawing of some craft while rolling could render a desired right
|
||||
// turn into a desired left turn. Making the turn direction based on
|
||||
// current roll angle keeps the plane committed to a direction once chosen
|
||||
if (courseError < -180.0f + (fixedwingpathfollowerSettings.ReverseCourseOverlap * 0.5f)
|
||||
&& attitudeState.Roll > 0.0f) {
|
||||
courseError += 360.0f;
|
||||
}
|
||||
if (courseError > 180.0f - (fixedwingpathfollowerSettings.ReverseCourseOverlap * 0.5f)
|
||||
&& attitudeState.Roll < 0.0f) {
|
||||
courseError -= 360.0f;
|
||||
}
|
||||
|
||||
courseIntegral = boundf(courseIntegral + courseError * dT * fixedwingpathfollowerSettings.CoursePI.Ki,
|
||||
-fixedwingpathfollowerSettings.CoursePI.ILimit,
|
||||
fixedwingpathfollowerSettings.CoursePI.ILimit);
|
||||
@ -628,7 +625,7 @@ static uint8_t updateFixedDesiredAttitude()
|
||||
* Compute desired yaw command
|
||||
*/
|
||||
// TODO implement raw control mode for yaw and base on Accels.Y
|
||||
stabDesired.Yaw = 0;
|
||||
stabDesired.Yaw = 0.0f;
|
||||
|
||||
|
||||
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
@ -656,10 +653,116 @@ static void airspeedStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
|
||||
AirspeedStateGet(&airspeedState);
|
||||
VelocityStateGet(&velocityState);
|
||||
float groundspeed = sqrtf(velocityState.East * velocityState.East + velocityState.North * velocityState.North);
|
||||
float airspeedVector[2];
|
||||
float yaw;
|
||||
AttitudeStateYawGet(&yaw);
|
||||
airspeedVector[0] = cos_lookup_deg(yaw);
|
||||
airspeedVector[1] = sin_lookup_deg(yaw);
|
||||
// vector projection of groundspeed on airspeed vector to handle both forward and backwards movement
|
||||
float groundspeedProjection = velocityState.North * airspeedVector[0] + velocityState.East * airspeedVector[1];
|
||||
|
||||
|
||||
indicatedAirspeedStateBias = airspeedState.CalibratedAirspeed - groundspeed;
|
||||
// note - we do fly by Indicated Airspeed (== calibrated airspeed)
|
||||
// however since airspeed is updated less often than groundspeed, we use sudden changes to groundspeed to offset the airspeed by the same measurement.
|
||||
indicatedAirspeedStateBias = airspeedState.CalibratedAirspeed - groundspeedProjection;
|
||||
// note - we do fly by Indicated Airspeed (== calibrated airspeed) however
|
||||
// since airspeed is updated less often than groundspeed, we use sudden
|
||||
// changes to groundspeed to offset the airspeed by the same measurement.
|
||||
// This has a side effect that in the absence of any airspeed updates, the
|
||||
// pathfollower will fly using groundspeed.
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Function to calculate course vector C based on airspeed s, fluid movement F
|
||||
* and desired movement vector V
|
||||
* parameters in: V,F,s
|
||||
* parameters out: C
|
||||
* returns true if a valid solution could be found for V,F,s, false if not
|
||||
* C will be set to a best effort attempt either way
|
||||
*/
|
||||
static bool correctCourse(float *C, float *V, float *F, float s)
|
||||
{
|
||||
// Approach:
|
||||
// Let Sc be a circle around origin marking possible movement vectors
|
||||
// of the craft with airspeed s (all possible options for C)
|
||||
// Let Vl be a line through the origin along movement vector V where fr any
|
||||
// point v on line Vl v = k * (V / |V|) = k' * V
|
||||
// Let Wl be a line parallel to Vl where for any point v on line Vl exists
|
||||
// a point w on WL with w = v - F
|
||||
// Then any intersection between circle Sc and line Wl represents course
|
||||
// vector which would result in a movement vector
|
||||
// V' = k * ( V / |V|) = k' * V
|
||||
// If there is no intersection point, S is insufficient to compensate
|
||||
// for F and we can only try to fly in direction of V (thus having wind drift
|
||||
// but at least making progress orthogonal to wind)
|
||||
|
||||
s = fabsf(s);
|
||||
float f = sqrtf(F[0] * F[0] + F[1] * F[1]);
|
||||
|
||||
// normalize Cn=V/|V|, |V| must be >0
|
||||
float v = sqrtf(V[0] * V[0] + V[1] * V[1]);
|
||||
if (v < 1e-6f) {
|
||||
// if |V|=0, we aren't supposed to move, turn into the wind
|
||||
// (this allows hovering)
|
||||
C[0] = -F[0];
|
||||
C[1] = -F[1];
|
||||
// if desired airspeed matches fluidmovement a hover is actually
|
||||
// intended so return true
|
||||
return fabsf(f - s) < 1e-3f;
|
||||
}
|
||||
float Vn[2] = { V[0] / v, V[1] / v };
|
||||
|
||||
// project F on V
|
||||
float fp = F[0] * Vn[0] + F[1] * Vn[1];
|
||||
|
||||
// find component Fo of F that is orthogonal to V
|
||||
// (which is exactly the distance between Vl and Wl)
|
||||
float Fo[2] = { F[0] - (fp * Vn[0]), F[1] - (fp * Vn[1]) };
|
||||
float fo2 = Fo[0] * Fo[0] + Fo[1] * Fo[1];
|
||||
|
||||
// find k where k * Vn = C - Fo
|
||||
// |C|=s is the hypothenuse in any rectangular triangle formed by k * Vn and Fo
|
||||
// so k^2 + fo^2 = s^2 (since |Vn|=1)
|
||||
float k2 = s * s - fo2;
|
||||
if (k2 <= -1e-3f) {
|
||||
// there is no solution, we will be drifted off either way
|
||||
// fallback: fly stupidly in direction of V and hope for the best
|
||||
C[0] = V[0];
|
||||
C[1] = V[1];
|
||||
return false;
|
||||
} else if (k2 <= 1e-3f) {
|
||||
// there is exactly one solution: -Fo
|
||||
C[0] = -Fo[0];
|
||||
C[1] = -Fo[1];
|
||||
return true;
|
||||
}
|
||||
// we have two possible solutions k positive and k negative as there are
|
||||
// two intersection points between Wl and Sc
|
||||
// which one is better? two criteria:
|
||||
// 1. we MUST move in the right direction, if any k leads to -v its invalid
|
||||
// 2. we should minimize the speed error
|
||||
float k = sqrt(k2);
|
||||
float C1[2] = { -k * Vn[0] - Fo[0], -k * Vn[1] - Fo[1] };
|
||||
float C2[2] = { k *Vn[0] - Fo[0], k * Vn[1] - Fo[1] };
|
||||
// project C+F on Vn to find signed resulting movement vector length
|
||||
float vp1 = (C1[0] + F[0]) * Vn[0] + (C1[1] + F[1]) * Vn[1];
|
||||
float vp2 = (C2[0] + F[0]) * Vn[0] + (C2[1] + F[1]) * Vn[1];
|
||||
if (vp1 >= 0.0f && fabsf(v - vp1) < fabsf(v - vp2)) {
|
||||
// in this case the angle between course and resulting movement vector
|
||||
// is greater than 90 degrees - so we actually fly backwards
|
||||
C[0] = C1[0];
|
||||
C[1] = C1[1];
|
||||
return true;
|
||||
}
|
||||
C[0] = C2[0];
|
||||
C[1] = C2[1];
|
||||
if (vp2 >= 0.0f) {
|
||||
// in this case the angle between course and movement vector is less than
|
||||
// 90 degrees, but we do move in the right direction
|
||||
return true;
|
||||
} else {
|
||||
// in this case we actually get driven in the opposite direction of V
|
||||
// with both solutions for C
|
||||
// this might be reached in headwind stronger than maximum allowed
|
||||
// airspeed.
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -75,6 +75,18 @@ void pathFollowerHandler(bool newinit);
|
||||
*/
|
||||
void pathPlannerHandler(bool newinit);
|
||||
|
||||
/**
|
||||
* @brief Handler to setup takeofflocation on arming. it is set up during Arming
|
||||
* @input: NONE:
|
||||
* @output: NONE
|
||||
*/
|
||||
void takeOffLocationHandler();
|
||||
|
||||
/**
|
||||
* @brief Initialize TakeoffLocationHanlder
|
||||
*/
|
||||
void takeOffLocationHandlerInit();
|
||||
|
||||
/*
|
||||
* These are assumptions we make in the flight code about the order of settings and their consistency between
|
||||
* objects. Please keep this synchronized to the UAVObjects
|
||||
@ -91,7 +103,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
@ -108,7 +120,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION2SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
@ -125,7 +137,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION3SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
@ -142,7 +154,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION4SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
@ -159,7 +171,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION5SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
@ -176,7 +188,7 @@ void pathPlannerHandler(bool newinit);
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYRATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_RELAYATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_ALTITUDEHOLD == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_VERTICALVELOCITY == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_ALTITUDEVARIO == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) && \
|
||||
((int)FLIGHTMODESETTINGS_STABILIZATION6SETTINGS_CRUISECONTROL == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL) && \
|
||||
1 \
|
||||
)
|
||||
|
@ -134,6 +134,9 @@ int32_t ManualControlStart()
|
||||
// Make sure unarmed on power up
|
||||
armHandler(true);
|
||||
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
takeOffLocationHandlerInit();
|
||||
#endif
|
||||
// Start main task
|
||||
PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle);
|
||||
|
||||
@ -167,7 +170,9 @@ static void manualControlTask(void)
|
||||
{
|
||||
// Process Arming
|
||||
armHandler(false);
|
||||
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
takeOffLocationHandler();
|
||||
#endif
|
||||
// Process flight mode
|
||||
FlightStatusData flightStatus;
|
||||
|
||||
@ -200,9 +205,13 @@ static void manualControlTask(void)
|
||||
break;
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOFPV:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOLOS:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIONSEW:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POI:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
|
||||
handler = &handler_PATHFOLLOWER;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
|
||||
|
@ -35,8 +35,9 @@
|
||||
#include <positionstate.h>
|
||||
#include <flightmodesettings.h>
|
||||
|
||||
|
||||
#if defined(REVOLUTION)
|
||||
#include <plans.h>
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
@ -51,69 +52,63 @@
|
||||
void pathFollowerHandler(bool newinit)
|
||||
{
|
||||
if (newinit) {
|
||||
PathDesiredInitialize();
|
||||
PositionStateInitialize();
|
||||
plan_initialize();
|
||||
}
|
||||
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
uint8_t flightMode;
|
||||
FlightStatusFlightModeGet(&flightMode);
|
||||
|
||||
if (newinit) {
|
||||
// After not being in this mode for a while init at current height
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
FlightModeSettingsData settings;
|
||||
FlightModeSettingsGet(&settings);
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
switch (flightStatus.FlightMode) {
|
||||
switch (flightMode) {
|
||||
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
|
||||
// Simple Return To Base mode - keep altitude the same, fly to home position
|
||||
|
||||
|
||||
pathDesired.Start.North = 0;
|
||||
pathDesired.Start.East = 0;
|
||||
pathDesired.Start.Down = positionState.Down - settings.ReturnToHomeAltitudeOffset;
|
||||
pathDesired.End.North = 0;
|
||||
pathDesired.End.East = 0;
|
||||
pathDesired.End.Down = positionState.Down - settings.ReturnToHomeAltitudeOffset;
|
||||
pathDesired.StartingVelocity = 1;
|
||||
pathDesired.EndingVelocity = 0;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
plan_setup_returnToBase();
|
||||
break;
|
||||
default:
|
||||
|
||||
pathDesired.Start.North = positionState.North;
|
||||
pathDesired.Start.East = positionState.East;
|
||||
pathDesired.Start.Down = positionState.Down;
|
||||
pathDesired.End.North = positionState.North;
|
||||
pathDesired.End.East = positionState.East;
|
||||
pathDesired.End.Down = positionState.Down;
|
||||
pathDesired.StartingVelocity = 1;
|
||||
pathDesired.EndingVelocity = 0;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
/* Disable this section, until such time as proper discussion can be had about how to implement it for all types of crafts.
|
||||
} else {
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
pathDesired.End[PATHDESIRED_END_NORTH] += dT * -cmd->Pitch;
|
||||
pathDesired.End[PATHDESIRED_END_EAST] += dT * cmd->Roll;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
PathDesiredSet(&pathDesired);
|
||||
*/
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
|
||||
plan_setup_positionHold();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOFPV:
|
||||
plan_setup_PositionVarioFPV();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOLOS:
|
||||
plan_setup_PositionVarioLOS();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIONSEW:
|
||||
plan_setup_PositionVarioNSEW();
|
||||
break;
|
||||
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
plan_setup_land();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
|
||||
plan_setup_AutoCruise();
|
||||
break;
|
||||
|
||||
default:
|
||||
plan_setup_positionHold();
|
||||
break;
|
||||
}
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
|
||||
// special handling of autoland - behaves like positon hold but with slow altitude decrease
|
||||
if (flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_LAND) {
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
PathDesiredData pathDesired;
|
||||
PathDesiredGet(&pathDesired);
|
||||
pathDesired.End.Down = positionState.Down + 5;
|
||||
PathDesiredSet(&pathDesired);
|
||||
switch (flightMode) {
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOFPV:
|
||||
plan_run_PositionVarioFPV();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOLOS:
|
||||
plan_run_PositionVarioLOS();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIONSEW:
|
||||
plan_run_PositionVarioNSEW();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
plan_run_land();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
|
||||
plan_run_AutoCruise();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
125
flight/modules/ManualControl/takeofflocationhandler.c
Normal file
125
flight/modules/ManualControl/takeofflocationhandler.c
Normal file
@ -0,0 +1,125 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file takeofflocationhandler.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief handles TakeOffLocation
|
||||
* --
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "inc/manualcontrol.h"
|
||||
#include <stdint.h>
|
||||
#include <flightstatus.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <positionstate.h>
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static bool locationSet;
|
||||
// Private functions
|
||||
static void SetTakeOffLocation();
|
||||
|
||||
void takeOffLocationHandlerInit()
|
||||
{
|
||||
TakeOffLocationInitialize();
|
||||
// check whether there is a preset/valid takeoff location
|
||||
uint8_t mode;
|
||||
uint8_t status;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
TakeOffLocationStatusGet(&status);
|
||||
// preset with invalid location will actually behave like FirstTakeoff
|
||||
if (mode == TAKEOFFLOCATION_MODE_PRESET && status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
locationSet = true;
|
||||
} else {
|
||||
locationSet = false;
|
||||
status = TAKEOFFLOCATION_STATUS_INVALID;
|
||||
TakeOffLocationStatusSet(&status);
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Handles TakeOffPosition location setup
|
||||
* @param newinit
|
||||
*/
|
||||
void takeOffLocationHandler()
|
||||
{
|
||||
uint8_t armed;
|
||||
uint8_t status;
|
||||
|
||||
FlightStatusArmedGet(&armed);
|
||||
|
||||
// Location already acquired/preset
|
||||
if (armed == FLIGHTSTATUS_ARMED_ARMED && locationSet) {
|
||||
return;
|
||||
}
|
||||
|
||||
TakeOffLocationStatusGet(&status);
|
||||
|
||||
switch (armed) {
|
||||
case FLIGHTSTATUS_ARMED_ARMING:
|
||||
case FLIGHTSTATUS_ARMED_ARMED:
|
||||
if (!locationSet || status != TAKEOFFLOCATION_STATUS_VALID) {
|
||||
uint8_t mode;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
|
||||
if ((mode != TAKEOFFLOCATION_MODE_PRESET) || (status == TAKEOFFLOCATION_STATUS_INVALID)) {
|
||||
SetTakeOffLocation();
|
||||
} else {
|
||||
locationSet = true;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case FLIGHTSTATUS_ARMED_DISARMED:
|
||||
// unset if location is to be acquired at each arming
|
||||
if (locationSet) {
|
||||
uint8_t mode;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
if (mode == TAKEOFFLOCATION_MODE_ARMINGLOCATION) {
|
||||
locationSet = false;
|
||||
status = TAKEOFFLOCATION_STATUS_INVALID;
|
||||
TakeOffLocationStatusSet(&status);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve TakeOffLocation from current PositionStatus
|
||||
*/
|
||||
void SetTakeOffLocation()
|
||||
{
|
||||
TakeOffLocationData takeOffLocation;
|
||||
|
||||
TakeOffLocationGet(&takeOffLocation);
|
||||
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
|
||||
takeOffLocation.North = positionState.North;
|
||||
takeOffLocation.East = positionState.East;
|
||||
takeOffLocation.Down = positionState.Down;
|
||||
takeOffLocation.Status = TAKEOFFLOCATION_STATUS_VALID;
|
||||
|
||||
TakeOffLocationSet(&takeOffLocation);
|
||||
locationSet = true;
|
||||
}
|
@ -45,6 +45,7 @@
|
||||
#include "flightmodesettings.h"
|
||||
#include <pios_struct_helper.h>
|
||||
#include "paths.h"
|
||||
#include "plans.h"
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 1024
|
||||
@ -89,6 +90,7 @@ static bool pathplanner_active = false;
|
||||
*/
|
||||
int32_t PathPlannerStart()
|
||||
{
|
||||
plan_initialize();
|
||||
// when the active waypoint changes, update pathDesired
|
||||
WaypointConnectCallback(commandUpdated);
|
||||
WaypointActiveConnectCallback(commandUpdated);
|
||||
@ -169,21 +171,7 @@ static void pathPlannerTask()
|
||||
if (!failsafeRTHset) {
|
||||
failsafeRTHset = 1;
|
||||
// copy pasta: same calculation as in manualcontrol, set return to home coordinates
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
FlightModeSettingsData settings;
|
||||
FlightModeSettingsGet(&settings);
|
||||
|
||||
pathDesired.Start.North = 0;
|
||||
pathDesired.Start.East = 0;
|
||||
pathDesired.Start.Down = positionState.Down - settings.ReturnToHomeAltitudeOffset;
|
||||
pathDesired.End.North = 0;
|
||||
pathDesired.End.East = 0;
|
||||
pathDesired.End.Down = positionState.Down - settings.ReturnToHomeAltitudeOffset;
|
||||
pathDesired.StartingVelocity = 1;
|
||||
pathDesired.EndingVelocity = 0;
|
||||
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
|
||||
PathDesiredSet(&pathDesired);
|
||||
plan_setup_positionHold();
|
||||
}
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_PATHPLAN, SYSTEMALARMS_ALARM_ERROR);
|
||||
|
||||
|
@ -62,6 +62,7 @@
|
||||
#include <CoordinateConversions.h>
|
||||
|
||||
#include <pios_board_info.h>
|
||||
#include <pios_struct_helper.h>
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 1000
|
||||
@ -474,35 +475,7 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv)
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
Quaternion2R(rotationQuat, R);
|
||||
|
||||
mag_transform[0][0] = R[0][0] * cal.mag_transform.r0c0 +
|
||||
R[1][0] * cal.mag_transform.r0c1 +
|
||||
R[2][0] * cal.mag_transform.r0c2;
|
||||
mag_transform[0][1] = R[0][1] * cal.mag_transform.r0c0 +
|
||||
R[1][1] * cal.mag_transform.r0c1 +
|
||||
R[2][1] * cal.mag_transform.r0c2;
|
||||
mag_transform[0][2] = R[0][2] * cal.mag_transform.r0c0 +
|
||||
R[1][2] * cal.mag_transform.r0c1 +
|
||||
R[2][2] * cal.mag_transform.r0c2;
|
||||
|
||||
mag_transform[1][0] = R[0][0] * cal.mag_transform.r1c0 +
|
||||
R[1][0] * cal.mag_transform.r1c1 +
|
||||
R[2][0] * cal.mag_transform.r1c2;
|
||||
mag_transform[1][1] = R[0][1] * cal.mag_transform.r1c0 +
|
||||
R[1][1] * cal.mag_transform.r1c1 +
|
||||
R[2][1] * cal.mag_transform.r1c2;
|
||||
mag_transform[1][2] = R[0][2] * cal.mag_transform.r1c0 +
|
||||
R[1][2] * cal.mag_transform.r1c1 +
|
||||
R[2][2] * cal.mag_transform.r1c2;
|
||||
|
||||
mag_transform[1][0] = R[0][0] * cal.mag_transform.r2c0 +
|
||||
R[1][0] * cal.mag_transform.r2c1 +
|
||||
R[2][0] * cal.mag_transform.r2c2;
|
||||
mag_transform[2][1] = R[0][1] * cal.mag_transform.r2c0 +
|
||||
R[1][1] * cal.mag_transform.r2c1 +
|
||||
R[2][1] * cal.mag_transform.r2c2;
|
||||
mag_transform[2][2] = R[0][2] * cal.mag_transform.r2c0 +
|
||||
R[1][2] * cal.mag_transform.r2c1 +
|
||||
R[2][2] * cal.mag_transform.r2c2;
|
||||
matrix_mult_3x3f((float(*)[3])cast_struct_to_array(cal.mag_transform, cal.mag_transform.r0c0), R, mag_transform);
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
|
@ -247,7 +247,7 @@ static void stabilizationOuterloopTask()
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE:
|
||||
rateDesiredAxis[t] = stabilizationAltitudeHold(stabilizationDesiredAxis[t], ALTITUDEHOLD, reinit);
|
||||
break;
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_VERTICALVELOCITY:
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDEVARIO:
|
||||
rateDesiredAxis[t] = stabilizationAltitudeHold(stabilizationDesiredAxis[t], ALTITUDEVARIO, reinit);
|
||||
break;
|
||||
#endif /* REVOLUTION */
|
||||
|
@ -174,8 +174,8 @@ static void StabilizationDesiredUpdatedCb(__attribute__((unused)) UAVObjEvent *e
|
||||
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE;
|
||||
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL;
|
||||
break;
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_VERTICALVELOCITY:
|
||||
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_VERTICALVELOCITY;
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO:
|
||||
cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDEVARIO;
|
||||
cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL;
|
||||
break;
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL:
|
||||
|
@ -82,6 +82,7 @@ ifndef TESTAPP
|
||||
|
||||
## Misc library functions
|
||||
SRC += $(FLIGHTLIB)/paths.c
|
||||
SRC += $(FLIGHTLIB)/plans.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
|
||||
|
@ -113,6 +113,7 @@ UAVOBJSRCFILENAMES += poilocation
|
||||
UAVOBJSRCFILENAMES += poilearnsettings
|
||||
UAVOBJSRCFILENAMES += mpu6000settings
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
UAVOBJSRCFILENAMES += takeofflocation
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -84,6 +84,7 @@ ifndef TESTAPP
|
||||
|
||||
## Misc library functions
|
||||
SRC += $(FLIGHTLIB)/paths.c
|
||||
SRC += $(FLIGHTLIB)/plans.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
|
||||
|
@ -113,6 +113,7 @@ UAVOBJSRCFILENAMES += poilocation
|
||||
UAVOBJSRCFILENAMES += poilearnsettings
|
||||
UAVOBJSRCFILENAMES += mpu6000settings
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
UAVOBJSRCFILENAMES += takeofflocation
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -83,6 +83,7 @@ ifndef TESTAPP
|
||||
|
||||
## Misc library functions
|
||||
SRC += $(FLIGHTLIB)/paths.c
|
||||
SRC += $(FLIGHTLIB)/plans.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
|
||||
|
@ -113,6 +113,7 @@ UAVOBJSRCFILENAMES += poilocation
|
||||
UAVOBJSRCFILENAMES += poilearnsettings
|
||||
UAVOBJSRCFILENAMES += mpu6000settings
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
UAVOBJSRCFILENAMES += takeofflocation
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -94,6 +94,7 @@ SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
SRC += $(FLIGHTLIB)/paths.c
|
||||
SRC += $(FLIGHTLIB)/plans.c
|
||||
SRC += $(FLIGHTLIB)/sanitycheck.c
|
||||
|
||||
SRC += $(MATHLIB)/sin_lookup.c
|
||||
|
@ -111,6 +111,7 @@ UAVOBJSRCFILENAMES += revosettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdstatus
|
||||
UAVOBJSRCFILENAMES += ekfconfiguration
|
||||
UAVOBJSRCFILENAMES += ekfstatevariance
|
||||
UAVOBJSRCFILENAMES += takeofflocation
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -2582,7 +2582,7 @@
|
||||
<type>splitter</type>
|
||||
</side1>
|
||||
<splitterOrientation>2</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf)</splitterSizes>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABqQAAAAIAAADm)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
@ -2759,7 +2759,7 @@
|
||||
<type>uavGadget</type>
|
||||
</side1>
|
||||
<splitterOrientation>1</splitterOrientation>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM)</splitterSizes>
|
||||
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAxwAAAAIAAAFi)</splitterSizes>
|
||||
<type>splitter</type>
|
||||
</side0>
|
||||
<side1>
|
||||
|
@ -10,7 +10,7 @@
|
||||
xmlns:xlink="http://www.w3.org/1999/xlink"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
width="94.2584"
|
||||
width="113.03149"
|
||||
height="79.57505"
|
||||
id="svg3604"
|
||||
version="1.1"
|
||||
@ -27,10 +27,10 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="29.851822"
|
||||
inkscape:cx="82.604436"
|
||||
inkscape:cy="54.252252"
|
||||
inkscape:current-layer="background"
|
||||
inkscape:zoom="5.2771064"
|
||||
inkscape:cx="50.100274"
|
||||
inkscape:cy="37.563212"
|
||||
inkscape:current-layer="layer36"
|
||||
id="namedview3608"
|
||||
showgrid="true"
|
||||
inkscape:window-width="1366"
|
||||
@ -40,7 +40,8 @@
|
||||
inkscape:window-maximized="1"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true"
|
||||
inkscape:snap-global="false">
|
||||
inkscape:snap-global="false"
|
||||
units="mm">
|
||||
<sodipodi:guide
|
||||
id="guide3857"
|
||||
position="68.372091,-63.708224"
|
||||
@ -59,10 +60,14 @@
|
||||
orientation="0,1" />
|
||||
<inkscape:grid
|
||||
type="xygrid"
|
||||
id="grid4540" />
|
||||
id="grid4540"
|
||||
empspacing="5"
|
||||
visible="true"
|
||||
enabled="true"
|
||||
snapvisiblegridlinesonly="true" />
|
||||
<sodipodi:guide
|
||||
orientation="0,1"
|
||||
position="86.912617,26.949779"
|
||||
position="78.262587,27.098184"
|
||||
id="guide4221" />
|
||||
</sodipodi:namedview>
|
||||
<defs
|
||||
@ -693,419 +698,391 @@
|
||||
inkscape:groupmode="layer"
|
||||
inkscape:label="Background">
|
||||
<rect
|
||||
ry="1.6285406"
|
||||
y="344.53958"
|
||||
x="497.92484"
|
||||
height="79.056633"
|
||||
width="95.066467"
|
||||
ry="1.6267107"
|
||||
y="344.58401"
|
||||
x="497.96927"
|
||||
height="78.967804"
|
||||
width="112.71937"
|
||||
id="Background"
|
||||
style="fill:#483737;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
style="fill:#918a6f;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.09500301;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<rect
|
||||
style="fill:#333333;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-5-1"
|
||||
width="40.113979"
|
||||
height="13.206578"
|
||||
x="569.19208"
|
||||
y="380.45892"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#333333;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-9-3"
|
||||
width="62.110886"
|
||||
height="13.206578"
|
||||
x="547.19519"
|
||||
y="394.70282"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#323232;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-0"
|
||||
width="109.66098"
|
||||
height="13.853112"
|
||||
x="499.64511"
|
||||
y="345.93436"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#333333;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-5"
|
||||
width="68.523476"
|
||||
height="13.206578"
|
||||
x="499.64508"
|
||||
y="380.45892"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#333333;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-9"
|
||||
width="46.00037"
|
||||
height="13.206578"
|
||||
x="499.64508"
|
||||
y="394.70282"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#323232;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-0-7"
|
||||
width="109.64501"
|
||||
height="13.853112"
|
||||
x="499.66107"
|
||||
y="360.58862"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4550-8-7-82"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="547.97754"
|
||||
y="411.38937"
|
||||
y="411.27975"
|
||||
ry="1" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none"
|
||||
style="fill:#333333;fill-opacity:1;stroke:none"
|
||||
id="rect1234"
|
||||
width="63.478992"
|
||||
height="12.219843"
|
||||
x="527.70123"
|
||||
y="409.64447"
|
||||
width="109.5812"
|
||||
height="13.206578"
|
||||
x="499.72488"
|
||||
y="408.94675"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none"
|
||||
id="Receiver"
|
||||
width="19.129522"
|
||||
height="10.639811"
|
||||
x="504.99179"
|
||||
y="387.5629"
|
||||
ry="0.24124773"
|
||||
inkscape:label="#rect4550" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-7"
|
||||
width="37.799622"
|
||||
height="13.255064"
|
||||
x="553.24451"
|
||||
y="395.2457"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-4"
|
||||
width="63.468098"
|
||||
height="12.839675"
|
||||
x="527.57617"
|
||||
y="381.38202"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-0"
|
||||
width="91.066727"
|
||||
height="13.183137"
|
||||
x="499.96637"
|
||||
y="346.05209"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-0-9"
|
||||
width="91.019348"
|
||||
height="13.183137"
|
||||
x="500.06686"
|
||||
y="360.27713"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4358-7-4"
|
||||
width="24.646557"
|
||||
height="13.221018"
|
||||
x="527.58087"
|
||||
y="395.29047"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="CPUOverload"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="532.78839"
|
||||
y="411.4689"
|
||||
ry="1"
|
||||
width="19.142458"
|
||||
height="9.4961557"
|
||||
x="588.72668"
|
||||
y="410.80194"
|
||||
ry="1.111892"
|
||||
inkscape:label="#rect4550-8" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="OutOfMemory"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="544.5553"
|
||||
y="411.4689"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-7" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="StackOverflow"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="556.32214"
|
||||
y="411.4689"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="EventSystem"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="568.08905"
|
||||
y="411.4689"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-15" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="I2C"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="579.8559"
|
||||
y="411.4689"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-2" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="521.74384"
|
||||
y="379.36826"
|
||||
x="529.24725"
|
||||
y="379.43469"
|
||||
id="text5334"
|
||||
sodipodi:linespacing="125%"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4263"
|
||||
x="521.74384"
|
||||
y="379.36826">SYSTEM HEALTH</tspan></text>
|
||||
x="529.24725"
|
||||
y="379.43469">SYSTEM HEALTH</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-426.01138"
|
||||
y="440.49539"
|
||||
x="-426.10474"
|
||||
y="440.35391"
|
||||
id="text4641-5-2"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5401"
|
||||
x="-426.01138"
|
||||
y="440.49539">Sensors</tspan></text>
|
||||
id="tspan5393"
|
||||
x="-426.10474"
|
||||
y="440.35391">SENSR</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-406.95456"
|
||||
y="440.47641"
|
||||
x="-408.18991"
|
||||
y="440.35474"
|
||||
id="text4641-5-2-5"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5424"
|
||||
x="-406.95456"
|
||||
y="440.47641">Auto</tspan></text>
|
||||
id="tspan5375"
|
||||
x="-408.18991"
|
||||
y="440.35474">AUTO</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-447.34424"
|
||||
y="464.44702"
|
||||
x="-463.11954"
|
||||
y="481.81909"
|
||||
id="text4641-5-2-1"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5435"
|
||||
x="-447.34424"
|
||||
y="464.44702">Misc.</tspan></text>
|
||||
id="tspan5383"
|
||||
x="-463.11954"
|
||||
y="481.81909">MISC</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-462.94199"
|
||||
y="464.46683"
|
||||
id="text4641-5-2-11"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5446"
|
||||
x="-462.94199"
|
||||
y="464.46683">Link</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-464.57455"
|
||||
y="486.72632"
|
||||
x="-462.91629"
|
||||
y="440.35474"
|
||||
id="text4641-5-2-2"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5469"
|
||||
x="-464.57455"
|
||||
y="486.72632">Power</tspan></text>
|
||||
id="tspan5387"
|
||||
x="-462.91629"
|
||||
y="440.35474">PWR</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-478.51532"
|
||||
y="464.46683"
|
||||
x="-478.508"
|
||||
y="440.35391"
|
||||
id="text4641-5-2-6"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4340"
|
||||
x="-478.51532"
|
||||
y="464.46683">Syst.</tspan></text>
|
||||
id="tspan5389"
|
||||
x="-478.508"
|
||||
y="440.35391">SYS</tspan></text>
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="BootFault"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="546.92853"
|
||||
y="382.58969"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-8" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect4550-8-1-4-21-9"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="561.6792"
|
||||
y="382.58969"
|
||||
ry="1" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect41234"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="576.42981"
|
||||
y="382.52267"
|
||||
ry="1.3167187"
|
||||
inkscape:label="#rect4550-8-1-4-21-2" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="FlightTime"
|
||||
width="15.447426"
|
||||
height="10.265867"
|
||||
x="574.46124"
|
||||
y="396.60678"
|
||||
ry="1"
|
||||
width="18.060333"
|
||||
height="10.19887"
|
||||
x="525.18445"
|
||||
y="396.2067"
|
||||
ry="0.99347377"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Telemetry"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="532.13593"
|
||||
y="396.63843"
|
||||
ry="1"
|
||||
width="33.123543"
|
||||
height="9.9680929"
|
||||
x="574.63525"
|
||||
y="382.0614"
|
||||
ry="0.97701645"
|
||||
inkscape:label="#rect4550-8-1-4-21-5" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Attitude"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="505.26666"
|
||||
y="347.495"
|
||||
ry="1"
|
||||
width="23.782648"
|
||||
height="10.03509"
|
||||
x="504.74219"
|
||||
y="347.8266"
|
||||
ry="0.98358321"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Stabilization"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="527.08551"
|
||||
y="347.495"
|
||||
ry="1"
|
||||
width="23.804651"
|
||||
height="10.068589"
|
||||
x="530.97595"
|
||||
y="347.79312"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-3" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Guidance"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="548.90442"
|
||||
y="347.495"
|
||||
ry="1"
|
||||
width="23.83815"
|
||||
height="10.068589"
|
||||
x="557.11407"
|
||||
y="347.8266"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-1" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="PathPlan"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="570.72327"
|
||||
y="347.495"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-2" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="GPS"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="505.26666"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.788395"
|
||||
height="10.102088"
|
||||
x="504.7757"
|
||||
y="362.44739"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Sensors"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="527.08551"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.8104"
|
||||
height="10.102088"
|
||||
x="530.96442"
|
||||
y="362.44739"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-41" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Airspeed"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="548.90442"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.751532"
|
||||
height="10.102088"
|
||||
x="557.14178"
|
||||
y="362.48087"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-13" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Magnetometer"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="570.72327"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.793158"
|
||||
height="10.102088"
|
||||
x="584.00055"
|
||||
y="362.44739"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-8" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Battery"
|
||||
width="15.447426"
|
||||
height="10.265867"
|
||||
x="557.75928"
|
||||
y="396.60678"
|
||||
ry="1"
|
||||
width="18.0655"
|
||||
height="10.232368"
|
||||
x="504.83118"
|
||||
y="396.17319"
|
||||
ry="0.99673688"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="SystemConfiguration"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="532.17792"
|
||||
y="382.58969"
|
||||
ry="1"
|
||||
width="23.271717"
|
||||
height="10.107105"
|
||||
x="552.43744"
|
||||
y="396.21909"
|
||||
ry="0.98050147"
|
||||
inkscape:label="#rect4550-8-1-4-21" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-1"
|
||||
width="26.147932"
|
||||
height="27.124466"
|
||||
x="500.06686"
|
||||
y="381.38202"
|
||||
ry="0" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-453.88235"
|
||||
y="440.49704"
|
||||
x="-444.87003"
|
||||
y="440.35474"
|
||||
id="text4641-5-2-11-0"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3467"
|
||||
x="-453.88235"
|
||||
y="440.49704">I/O</tspan></text>
|
||||
x="-444.87003"
|
||||
y="440.35474">I/O</tspan></text>
|
||||
<rect
|
||||
style="fill:#6c5353;fill-opacity:1;stroke:#6c5d53;stroke-width:0.66968507;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="rect3510"
|
||||
width="1.94293"
|
||||
height="7.3697343"
|
||||
x="12.260558"
|
||||
y="54.383957"
|
||||
transform="translate(497.66563,344.28037)" />
|
||||
x="531.36542"
|
||||
y="383.37735" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Receiver-OK-2"
|
||||
width="19.129522"
|
||||
height="10.639811"
|
||||
x="505.12875"
|
||||
y="382.42383"
|
||||
ry="1.0787175"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Receiver"
|
||||
width="23.149378"
|
||||
height="10.137329"
|
||||
x="504.79376"
|
||||
y="381.97681"
|
||||
ry="1.0277734"
|
||||
inkscape:label="#rect4550"
|
||||
rx="1.1054602" />
|
||||
<rect
|
||||
style="fill:#6c5d53;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect1234-1-1"
|
||||
width="26.147932"
|
||||
height="12.217504"
|
||||
x="500.06686"
|
||||
y="409.64682"
|
||||
ry="0" />
|
||||
<rect
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline"
|
||||
id="rect"
|
||||
width="19.129522"
|
||||
height="10.639811"
|
||||
x="504.98425"
|
||||
y="410.36182"
|
||||
ry="1.0787175"
|
||||
inkscape:label="#rect4550"
|
||||
rx="1.1054602" />
|
||||
rx="1.3377603" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="0.98606986"
|
||||
y="396.92505"
|
||||
x="505.28799"
|
||||
y="382.03198"
|
||||
x="530.21112"
|
||||
height="10.060461"
|
||||
width="18.729839"
|
||||
width="23.084681"
|
||||
id="Actuator"
|
||||
style="fill:#241c1c;fill-opacity:1;stroke:none;display:inline" />
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline" />
|
||||
<rect
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="OutOfMemory"
|
||||
width="19.07546"
|
||||
height="9.5296545"
|
||||
x="525.68011"
|
||||
y="410.76846"
|
||||
ry="1.1158142"
|
||||
inkscape:label="#rect4550-8" />
|
||||
<rect
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="StackOverflow"
|
||||
width="19.07546"
|
||||
height="9.4961557"
|
||||
x="546.75079"
|
||||
y="410.80194"
|
||||
ry="1.111892"
|
||||
inkscape:label="#rect4550-8" />
|
||||
<rect
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="EventSystem"
|
||||
width="19.07546"
|
||||
height="9.5296545"
|
||||
x="567.6875"
|
||||
y="410.76846"
|
||||
ry="1.1158142"
|
||||
inkscape:label="#rect4550-8" />
|
||||
<rect
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="BootFault"
|
||||
width="19.108959"
|
||||
height="9.5296545"
|
||||
x="504.70978"
|
||||
y="410.73495"
|
||||
ry="1.1158142"
|
||||
inkscape:label="#rect4550-8" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1.0047177"
|
||||
y="396.14725"
|
||||
x="578.25714"
|
||||
height="10.250717"
|
||||
width="13.477478"
|
||||
id="rect-1"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline" />
|
||||
<rect
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline"
|
||||
id="PathPlan"
|
||||
width="23.883144"
|
||||
height="10.135587"
|
||||
x="583.93506"
|
||||
y="347.75961"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-1" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1.008266"
|
||||
y="381.91876"
|
||||
x="555.55225"
|
||||
height="10.286918"
|
||||
width="11.346323"
|
||||
id="I2C"
|
||||
style="fill:#28170b;stroke:none;display:inline" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3.38406372px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#f4d7d7;fill-opacity:1;stroke:none;display:inline;font-family:Sans;-inkscape-font-specification:Sans Bold"
|
||||
x="-446.64218"
|
||||
y="501.22174"
|
||||
id="text4641-5-2-1-5"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="matrix(0,-0.87458357,1.1434013,0,0,0)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5472"
|
||||
x="-446.64218"
|
||||
y="501.22174">LINK</tspan></text>
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1.0080011"
|
||||
y="396.14725"
|
||||
x="594.28265"
|
||||
height="10.284216"
|
||||
width="13.544476"
|
||||
id="rect-2"
|
||||
style="fill:#28170b;fill-opacity:1;stroke:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer1"
|
||||
inkscape:label="GPS-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="GPS-OK"
|
||||
width="18.966711"
|
||||
width="23.804651"
|
||||
height="10.202584"
|
||||
x="505.26666"
|
||||
y="361.65591"
|
||||
x="7.0741663"
|
||||
y="18.133535"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
@ -1113,15 +1090,15 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer11"
|
||||
inkscape:label="Airspeed-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Airspeed-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.790537"
|
||||
height="10.102088"
|
||||
x="59.881477"
|
||||
y="18.179514"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
@ -1132,70 +1109,70 @@
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Magnetometer-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.057671"
|
||||
y="17.391815"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.135587"
|
||||
x="86.323196"
|
||||
y="18.162287"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer10"
|
||||
inkscape:label="Sensors-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Sensors-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.857534"
|
||||
height="10.135587"
|
||||
x="33.506733"
|
||||
y="18.146015"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer9"
|
||||
inkscape:label="PathPlan-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="PathPlan-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.05764"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.857534"
|
||||
height="10.102088"
|
||||
x="86.289665"
|
||||
y="3.5161142"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer8"
|
||||
inkscape:label="Guidance-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Guidance-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.135587"
|
||||
x="59.847977"
|
||||
y="3.5161142"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer7"
|
||||
inkscape:label="Stabilization-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Stabilization-OK"
|
||||
width="18.966711"
|
||||
width="23.824036"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="3.2146251"
|
||||
x="33.506733"
|
||||
y="3.4826155"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
@ -1203,88 +1180,88 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer6"
|
||||
inkscape:label="Attitude-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Attitude-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="7.6010327"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.135587"
|
||||
x="7.0985508"
|
||||
y="3.4826155"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer12"
|
||||
inkscape:label="SystemConfiguration-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="SystemConfiguration-OK"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="34.512287"
|
||||
y="38.309322"
|
||||
ry="1"
|
||||
width="23.259575"
|
||||
height="10.107105"
|
||||
x="54.779057"
|
||||
y="51.943333"
|
||||
ry="0.98050147"
|
||||
inkscape:label="#rect4550-8-1-4-21-1" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer13"
|
||||
inkscape:label="BootFault-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="BootFault-OK"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="49.262897"
|
||||
y="38.309322"
|
||||
ry="1" />
|
||||
width="19.072226"
|
||||
height="9.5041265"
|
||||
x="7.0544181"
|
||||
y="66.481804"
|
||||
ry="0.92200589" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer15"
|
||||
inkscape:label="Battery-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Battery-OK"
|
||||
width="15.447426"
|
||||
height="10.265867"
|
||||
x="60.093647"
|
||||
y="52.326412"
|
||||
ry="1"
|
||||
width="18.026833"
|
||||
height="10.165371"
|
||||
x="7.1983929"
|
||||
y="51.953167"
|
||||
ry="0.99021065"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer14"
|
||||
inkscape:label="Telemetry-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Telemetry-OK"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="34.470295"
|
||||
y="52.358059"
|
||||
ry="1"
|
||||
width="33.036205"
|
||||
height="10.03509"
|
||||
x="77.013763"
|
||||
y="37.752586"
|
||||
ry="0.98358321"
|
||||
inkscape:label="#rect4550-8-1-4-21-5" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer16"
|
||||
inkscape:label="FlightTime-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="FlightTime-OK"
|
||||
width="15.447426"
|
||||
width="18.060331"
|
||||
height="10.265867"
|
||||
x="76.795616"
|
||||
y="52.326412"
|
||||
x="27.518892"
|
||||
y="51.890926"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
@ -1292,123 +1269,122 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer21"
|
||||
inkscape:label="I2C-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="I2C-OK"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="82.190269"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="11.341881"
|
||||
height="10.315975"
|
||||
x="57.870148"
|
||||
y="37.609093"
|
||||
ry="1.2078834"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer20"
|
||||
inkscape:label="EventSystem-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="EventSystem-OK"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="70.423416"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.046602"
|
||||
height="9.5455027"
|
||||
x="70.088425"
|
||||
y="66.485054"
|
||||
ry="1.1176698"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer19"
|
||||
inkscape:label="StackOverflow-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="StackOverflow-OK"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="58.656513"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.046602"
|
||||
height="9.5790014"
|
||||
x="49.089085"
|
||||
y="66.42955"
|
||||
ry="1.1215922"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer18"
|
||||
inkscape:label="OutOfMemory-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="OutOfMemory-OK"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="46.889668"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.080101"
|
||||
height="9.4785051"
|
||||
x="28.080856"
|
||||
y="66.493179"
|
||||
ry="1.1098251"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer17"
|
||||
inkscape:label="CPUOverload-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="CPUOverload-OK"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="35.122761"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.147099"
|
||||
height="9.4785051"
|
||||
x="91.072304"
|
||||
y="66.503593"
|
||||
ry="1.1098251"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer22"
|
||||
inkscape:label="Receiver-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Receiver-OK"
|
||||
width="18.963711"
|
||||
height="10.260815"
|
||||
x="7.6226416"
|
||||
y="38.370422"
|
||||
ry="0.99888694"
|
||||
width="23.184559"
|
||||
height="10.160318"
|
||||
x="7.0866609"
|
||||
y="37.700447"
|
||||
ry="0.98910367"
|
||||
inkscape:label="#rect4550"
|
||||
rx="0.88121402" />
|
||||
rx="1.0773503" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer23"
|
||||
inkscape:label="Actuator-OK"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Actuator-OK"
|
||||
width="18.905607"
|
||||
width="23.26045"
|
||||
height="10.044919"
|
||||
x="7.6230011"
|
||||
y="52.617489"
|
||||
x="32.445606"
|
||||
y="37.744026"
|
||||
ry="1.112498"
|
||||
inkscape:label="#rect4550"
|
||||
rx="0.86747229" />
|
||||
rx="1.0672916" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5041"
|
||||
inkscape:label="GPS-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="GPS-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="505.26666"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.790537"
|
||||
height="10.068589"
|
||||
x="7.1320496"
|
||||
y="18.213015"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
@ -1419,11 +1395,11 @@
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Airspeed-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.068589"
|
||||
x="59.881477"
|
||||
y="18.213013"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
@ -1434,252 +1410,252 @@
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Magnetometer-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.091171"
|
||||
y="17.425316"
|
||||
ry="1"
|
||||
width="23.790537"
|
||||
height="10.135587"
|
||||
x="86.323196"
|
||||
y="18.162289"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5047"
|
||||
inkscape:label="Sensors-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Sensors-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.068589"
|
||||
x="33.506733"
|
||||
y="18.213015"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5050"
|
||||
inkscape:label="PathPlan-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="PathPlan-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.05764"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.857534"
|
||||
height="10.135587"
|
||||
x="86.261238"
|
||||
y="3.503633"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5053"
|
||||
inkscape:label="Guidance-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Guidance-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.857534"
|
||||
height="10.068589"
|
||||
x="59.845669"
|
||||
y="3.5428796"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5056"
|
||||
inkscape:label="Stabilization-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Stabilization-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.169086"
|
||||
x="33.448105"
|
||||
y="3.4873767"
|
||||
ry="0.99671662"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5059"
|
||||
inkscape:label="Attitude-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Attitude-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="7.6010327"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.790537"
|
||||
height="10.102088"
|
||||
x="7.0985508"
|
||||
y="3.5161142"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5062"
|
||||
inkscape:label="SystemConfiguration-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="SystemConfiguration-Warning"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="34.512287"
|
||||
y="38.309322"
|
||||
ry="1"
|
||||
width="23.326572"
|
||||
height="10.140604"
|
||||
x="54.759811"
|
||||
y="51.958912"
|
||||
ry="0.98375124"
|
||||
inkscape:label="#rect4550-8-1-4-21-1" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5065"
|
||||
inkscape:label="BootFault-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="BootFault-Warning"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="49.262897"
|
||||
y="38.309322"
|
||||
ry="1" />
|
||||
width="19.113802"
|
||||
height="9.550107"
|
||||
x="7.0522652"
|
||||
y="66.473434"
|
||||
ry="0.92646646" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5069"
|
||||
inkscape:label="Battery-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Battery-Warning"
|
||||
width="15.447426"
|
||||
height="10.265867"
|
||||
x="60.093647"
|
||||
y="52.326412"
|
||||
ry="1"
|
||||
width="17.993334"
|
||||
height="10.165371"
|
||||
x="7.2150578"
|
||||
y="51.908169"
|
||||
ry="0.99021065"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5072"
|
||||
inkscape:label="Telemetry-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Telemetry-Warning"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="34.470295"
|
||||
y="52.358059"
|
||||
ry="1"
|
||||
width="33.069702"
|
||||
height="9.9680929"
|
||||
x="77.01255"
|
||||
y="37.783974"
|
||||
ry="0.97701645"
|
||||
inkscape:label="#rect4550-8-1-4-21-5" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5075"
|
||||
inkscape:label="FlightTime-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="FlightTime-Warning"
|
||||
width="15.447426"
|
||||
height="10.265867"
|
||||
x="76.795616"
|
||||
y="52.326412"
|
||||
ry="1"
|
||||
width="18.060331"
|
||||
height="10.165371"
|
||||
x="27.54425"
|
||||
y="51.941666"
|
||||
ry="0.99021065"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5078"
|
||||
inkscape:label="I2C-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="I2C-Warning"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="82.190269"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="11.37538"
|
||||
height="10.315975"
|
||||
x="57.870148"
|
||||
y="37.609093"
|
||||
ry="1.2078834"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5081"
|
||||
inkscape:label="EventSystem-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="EventSystem-Warning"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="70.423416"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.069374"
|
||||
height="9.5117149"
|
||||
x="70.091797"
|
||||
y="66.525291"
|
||||
ry="1.1137137"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5084"
|
||||
inkscape:label="StackOverflow-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="StackOverflow-Warning"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="58.656513"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.116749"
|
||||
height="9.4406528"
|
||||
x="49.086876"
|
||||
y="66.548973"
|
||||
ry="1.1053932"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5087"
|
||||
inkscape:label="OutOfMemory-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="OutOfMemory-Warning"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="46.889668"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.116749"
|
||||
height="9.5354023"
|
||||
x="28.058323"
|
||||
y="66.477913"
|
||||
ry="1.1164871"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5090"
|
||||
inkscape:label="CPUOverload-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="CPUOverload-Warning"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="35.122761"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.140436"
|
||||
height="9.5354023"
|
||||
x="91.068588"
|
||||
y="66.494171"
|
||||
ry="1.1164871"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5093"
|
||||
inkscape:label="Receiver-Warning"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Receiver-Warning"
|
||||
width="18.821587"
|
||||
height="10.21344"
|
||||
x="7.7214546"
|
||||
y="38.403919"
|
||||
ry="0.79517722"
|
||||
width="23.142931"
|
||||
height="10.112944"
|
||||
x="7.1854739"
|
||||
y="37.700443"
|
||||
ry="0.78735298"
|
||||
inkscape:label="#rect4550"
|
||||
rx="0.8158862" />
|
||||
rx="1.0032097" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
@ -1689,28 +1665,27 @@
|
||||
<rect
|
||||
style="fill:#ff6600;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Actuator-Warning"
|
||||
width="18.91176"
|
||||
height="10.037488"
|
||||
x="7.6274734"
|
||||
y="52.645531"
|
||||
ry="0.92773163"
|
||||
width="23.233105"
|
||||
height="10.104486"
|
||||
x="32.485184"
|
||||
y="37.706322"
|
||||
ry="0.93392402"
|
||||
inkscape:label="#rect4550"
|
||||
rx="0.9812547" />
|
||||
rx="1.2054718" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5417"
|
||||
inkscape:label="GPS-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="GPS-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="505.26666"
|
||||
y="361.65591"
|
||||
ry="1"
|
||||
width="23.857534"
|
||||
height="10.135587"
|
||||
x="7.065052"
|
||||
y="18.146017"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
@ -1721,11 +1696,11 @@
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Airspeed-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.102088"
|
||||
x="59.904945"
|
||||
y="18.177544"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
@ -1736,55 +1711,55 @@
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Magnetometer-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.02417"
|
||||
y="17.391815"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.102088"
|
||||
x="86.290001"
|
||||
y="18.17181"
|
||||
ry="0.99014992"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5423"
|
||||
inkscape:label="Sensors-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Sensors-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="17.375544"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.135587"
|
||||
x="33.488335"
|
||||
y="18.155539"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5426"
|
||||
inkscape:label="PathPlan-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="PathPlan-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="73.05764"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.068589"
|
||||
x="86.2995"
|
||||
y="3.5313845"
|
||||
ry="0.98686653"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5429"
|
||||
inkscape:label="Guidance-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Guidance-Critical"
|
||||
width="18.966711"
|
||||
width="23.857534"
|
||||
height="10.202584"
|
||||
x="51.238789"
|
||||
y="3.2146251"
|
||||
x="59.858967"
|
||||
y="3.4538779"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
@ -1792,73 +1767,73 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="g5432"
|
||||
inkscape:label="Stabilization-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Stabilization-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="29.41988"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.824036"
|
||||
height="10.135587"
|
||||
x="33.504589"
|
||||
y="3.4826155"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5435"
|
||||
inkscape:label="Attitude-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Attitude-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="7.6010327"
|
||||
y="3.2146251"
|
||||
ry="1"
|
||||
width="23.790537"
|
||||
height="10.135587"
|
||||
x="7.1320496"
|
||||
y="3.5161142"
|
||||
ry="0.9934333"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5438"
|
||||
inkscape:label="SystemConfiguration-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="SystemConfiguration-Critical"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="34.512287"
|
||||
y="38.309322"
|
||||
ry="1"
|
||||
width="23.226076"
|
||||
height="10.107105"
|
||||
x="54.812557"
|
||||
y="51.97683"
|
||||
ry="0.98050147"
|
||||
inkscape:label="#rect4550-8-1-4-21-1" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5441"
|
||||
inkscape:label="BootFault-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="BootFault-Critical"
|
||||
width="13.310432"
|
||||
height="10.308098"
|
||||
x="49.262897"
|
||||
y="38.309322"
|
||||
ry="1" />
|
||||
width="19.139223"
|
||||
height="9.5711241"
|
||||
x="7.0209193"
|
||||
y="66.448311"
|
||||
ry="0.92850536" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5445"
|
||||
inkscape:label="Battery-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Battery-Critical"
|
||||
width="15.447426"
|
||||
width="18.060331"
|
||||
height="10.265867"
|
||||
x="60.093647"
|
||||
y="52.326412"
|
||||
x="7.165554"
|
||||
y="51.890926"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
@ -1866,29 +1841,29 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="g5448"
|
||||
inkscape:label="Telemetry-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Telemetry-Critical"
|
||||
width="18.966711"
|
||||
height="10.202584"
|
||||
x="34.470295"
|
||||
y="52.358059"
|
||||
ry="1"
|
||||
width="33.069702"
|
||||
height="10.001592"
|
||||
x="76.980263"
|
||||
y="37.752586"
|
||||
ry="0.98029983"
|
||||
inkscape:label="#rect4550-8-1-4-21-5" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5451"
|
||||
inkscape:label="FlightTime-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="FlightTime-Critical"
|
||||
width="15.447426"
|
||||
width="17.993334"
|
||||
height="10.265867"
|
||||
x="76.795616"
|
||||
y="52.326412"
|
||||
x="27.552391"
|
||||
y="51.85743"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8" />
|
||||
</g>
|
||||
@ -1896,92 +1871,92 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="g5454"
|
||||
inkscape:label="I2C-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="I2C-Critical"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="82.190269"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="11.37538"
|
||||
height="10.315975"
|
||||
x="57.870144"
|
||||
y="37.609093"
|
||||
ry="1.2078834"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5457"
|
||||
inkscape:label="EventSystem-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="EventSystem-Critical"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="70.423416"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.046602"
|
||||
height="9.5120039"
|
||||
x="70.088425"
|
||||
y="66.518555"
|
||||
ry="1.1137475"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5460"
|
||||
inkscape:label="StackOverflow-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="StackOverflow-Critical"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="58.656513"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.1136"
|
||||
height="9.5455027"
|
||||
x="49.075859"
|
||||
y="66.485054"
|
||||
ry="1.1176698"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5463"
|
||||
inkscape:label="OutOfMemory-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="OutOfMemory-Critical"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="46.889668"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.1136"
|
||||
height="9.5455027"
|
||||
x="28.063345"
|
||||
y="66.485054"
|
||||
ry="1.1176698"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5466"
|
||||
inkscape:label="CPUOverload-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="CPUOverload-Critical"
|
||||
width="10.470912"
|
||||
height="8.5405388"
|
||||
x="35.122761"
|
||||
y="67.18853"
|
||||
ry="1"
|
||||
width="19.1136"
|
||||
height="9.5120039"
|
||||
x="91.065742"
|
||||
y="66.485054"
|
||||
ry="1.1137475"
|
||||
inkscape:label="#rect4550-8" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g5469"
|
||||
inkscape:label="Receiver-Critical"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Receiver-Critical"
|
||||
width="18.940025"
|
||||
height="10.213441"
|
||||
x="7.6267047"
|
||||
y="38.417793"
|
||||
ry="1.1877477"
|
||||
width="23.194372"
|
||||
height="10.146443"
|
||||
x="7.090724"
|
||||
y="37.714317"
|
||||
ry="1.1799564"
|
||||
inkscape:label="#rect4550"
|
||||
rx="1.2082177" />
|
||||
rx="1.4796101" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
@ -1991,23 +1966,23 @@
|
||||
<rect
|
||||
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
|
||||
id="Actuator-Critical"
|
||||
width="18.874826"
|
||||
height="10.081664"
|
||||
x="7.663065"
|
||||
y="52.603611"
|
||||
ry="0.77868479"
|
||||
width="23.22967"
|
||||
height="10.148662"
|
||||
x="32.519169"
|
||||
y="37.663151"
|
||||
ry="0.78385955"
|
||||
inkscape:label="#rect4550"
|
||||
rx="0.79499185" />
|
||||
rx="0.97841418" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer5"
|
||||
inkscape:label="GPS-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="GPS-Error"
|
||||
inkscape:label="#g3406"
|
||||
transform="matrix(1.0377771,0,0,1,-0.27728602,0)">
|
||||
transform="matrix(1.303815,0,0,1.0006407,-2.9181954,0.76728593)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9"
|
||||
@ -2024,10 +1999,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer39"
|
||||
inkscape:label="PathPlan-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="PathPlan-Error"
|
||||
inkscape:label="#g3394">
|
||||
inkscape:label="#g3394"
|
||||
transform="matrix(1.3060972,0,0,1.0001794,-9.286657,0.26650193)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-34"
|
||||
@ -2044,10 +2020,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer38"
|
||||
inkscape:label="Guidance-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Guidance-Error"
|
||||
inkscape:label="#g3390">
|
||||
inkscape:label="#g3390"
|
||||
transform="matrix(1.3027754,0,0,1.0133326,-6.8947082,0.12363438)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-3"
|
||||
@ -2064,10 +2041,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer37"
|
||||
inkscape:label="Stabilization-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Stabilization-Error"
|
||||
inkscape:label="#g3386">
|
||||
inkscape:label="#g3386"
|
||||
transform="matrix(1.2992362,0,0,1.0066736,-4.7769775,0.17889491)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-7"
|
||||
@ -2084,11 +2062,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer3"
|
||||
inkscape:label="Airspeed-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Airspeed-Error"
|
||||
inkscape:label="#g3398"
|
||||
transform="matrix(1.0309004,0,0,1,-1.5754528,0)">
|
||||
transform="matrix(1.2972911,0,0,1.0167477,-6.6181285,0.34411746)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-79"
|
||||
@ -2110,7 +2088,7 @@
|
||||
style="display:inline"
|
||||
id="Magnetometer-Error"
|
||||
inkscape:label="#g3398"
|
||||
transform="matrix(1.0309004,0,0,1,20.190366,0.03602308)">
|
||||
transform="matrix(1.299095,0,0,1.0167223,19.677703,0.38071462)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-79-9"
|
||||
@ -2127,10 +2105,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer2"
|
||||
inkscape:label="Sensors-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Sensors-Error"
|
||||
inkscape:label="#g3402">
|
||||
inkscape:label="#g3402"
|
||||
transform="matrix(1.2955541,0,0,1.0099811,-4.6286669,0.49590947)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86"
|
||||
@ -2147,33 +2126,33 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer33"
|
||||
inkscape:label="Telemetry-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Telemetry-Error"
|
||||
inkscape:label="#g3422"
|
||||
transform="matrix(1.0343732,0,0,1,13.305779,0)">
|
||||
transform="matrix(1.011145,0,0,1,-1.2370971,0)"
|
||||
inkscape:label="#g4252">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86-4"
|
||||
d="M 20.794895,53.039633 39.08945,61.825066"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.1966573;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 77.702794,38.300164 32.588486,8.785433"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-5-4"
|
||||
d="M 20.83573,61.847333 39.066764,53.07372"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19377422;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 77.775534,47.107864 110.25087,38.334251"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer35"
|
||||
inkscape:label="Receiver-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="Receiver-Error"
|
||||
inkscape:label="#g3406"
|
||||
transform="matrix(1.0487144,0,0,1,-0.57430778,21.097426)">
|
||||
transform="matrix(1.2670269,0,0,1.0033347,-2.5810186,20.235292)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-2"
|
||||
@ -2190,231 +2169,229 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer34"
|
||||
inkscape:label="Actuator-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="Actuator-Error"
|
||||
inkscape:label="#g3406"
|
||||
transform="matrix(1.0377771,0,0,1,-0.32069392,35.147296)">
|
||||
transform="matrix(1,0,0,0.99018386,0,0.46977719)"
|
||||
inkscape:label="#g4238">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-1"
|
||||
d="M 7.9615204,18.056455 26.210275,26.874464"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19737208;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 32.903038,38.329601 23.045017,8.819383"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-4"
|
||||
d="M 7.9364397,26.848957 26.252147,18.055286"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19791019;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 32.871366,47.123473 56.000932,38.328432"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
id="I2C-Error"
|
||||
transform="matrix(0.9476726,0,0,0.98093768,3.3912844,0.88018434)"
|
||||
inkscape:label="#g4530">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-1-7"
|
||||
d="m 57.85366,38.087518 11.979058,9.144934"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-4-4"
|
||||
d="M 57.837196,47.205999 69.860204,38.086306"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer32"
|
||||
inkscape:label="Battery-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Battery-Error"
|
||||
inkscape:label="#g3426"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(0.99487041,0,0,0.96829624,0.0347729,1.7751095)"
|
||||
inkscape:label="#g4456">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86-0"
|
||||
d="m 46.502131,52.910887 14.610607,9.14342"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.09097731;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 7.5498082,52.475403 18.0821878,9.14342"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-5-6"
|
||||
d="M 46.442675,61.953487 61.145921,52.934252"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08697307;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 7.476225,61.518003 25.673064,52.498768"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer31"
|
||||
inkscape:label="FlightTime-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="FlightTime-Error"
|
||||
inkscape:label="#g3430"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(0.99485498,0,0,0.97451479,0.20647751,1.4858328)"
|
||||
inkscape:label="#g4450">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86-0-3"
|
||||
d="m 63.233236,52.875846 14.63044,9.079506"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08789504;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 27.859968,52.440362 45.94248,61.519868"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-5-6-7"
|
||||
d="m 63.192544,61.969763 14.647987,-9.06903"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.08791935;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 27.809675,61.534279 18.104198,-9.06903"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer30"
|
||||
inkscape:label="SystemConfiguration-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="SystemConfiguration-Error"
|
||||
inkscape:label="#g3414"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(1.0165533,0,0,0.96183155,-1.1730886,2.2079995)"
|
||||
inkscape:label="#g4438">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86-6"
|
||||
d="m 20.93643,38.821072 12.493301,9.22163"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01262045;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 55.345762,52.390536 22.824505,9.161262"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.36421418;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-end:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-5-1"
|
||||
d="M 20.937064,48.026792 33.498002,38.872801"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01214695;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 55.34692,61.535992 78.294994,52.441927"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.36357629;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-end:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer29"
|
||||
inkscape:label="BootFault-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="BootFault-Error"
|
||||
inkscape:label="#g3418"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(0.99024567,0,0,0.95640592,0.16475989,3.1867166)"
|
||||
inkscape:label="#g4462">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-86-6-8"
|
||||
d="m 35.705761,38.803039 12.45607,9.277316"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01467943;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 7.3536543,66.894221 26.479682,75.463174"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-5-1-9"
|
||||
d="M 35.66424,48.062824 48.169858,38.865363"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.01231074;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 7.2898997,75.446981 26.492007,66.951786"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer24"
|
||||
inkscape:label="Attitude-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="Attitude-Error"
|
||||
inkscape:label="#g3382"
|
||||
transform="matrix(1.0376867,0,0,1,-0.27616141,0)">
|
||||
inkscape:label="#g4230">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-8"
|
||||
d="M 7.9267385,3.9562181 26.225281,12.757016"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19783366;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 7.431639,4.1245053 31.174293,12.957929"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.36696184;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-9-4-9"
|
||||
d="M 7.9328239,12.666843 26.286235,3.9527152"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.19370687;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 7.4395349,12.867421 31.253381,4.1209894"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.36225235;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="g3109"
|
||||
inkscape:label="OutOfMemory-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="OutOfMemory-Error"
|
||||
inkscape:label="#g3442"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(0.99672458,0,0,0.95325152,0.02398426,3.264316)"
|
||||
inkscape:label="#g4468">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233"
|
||||
d="M 33.20487,75.243494 43.009818,67.67709"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80505109;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 28.467187,75.543139 47.482776,66.983913"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9"
|
||||
d="m 33.214298,67.65316 9.826498,7.608655"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81616998;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 28.485471,66.956843 19.057384,8.607021"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer28"
|
||||
inkscape:label="I2C-Error"
|
||||
style="display:inline">
|
||||
<g
|
||||
id="I2C-Error"
|
||||
inkscape:label="#g3454">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-09"
|
||||
d="m 68.473832,75.266428 9.874503,-7.54121"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80655557;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-0"
|
||||
d="m 68.55267,67.640417 9.780922,7.610454"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81437129;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
style="display:none" />
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer27"
|
||||
inkscape:label="EventSystem-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="EventSystem-Error"
|
||||
inkscape:label="#g3450"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(0.99998704,0,0,0.94992153,-0.13295657,3.5178711)"
|
||||
inkscape:label="#g4480">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-8"
|
||||
d="m 56.728611,75.196387 9.852857,-7.519565"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80451399;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 70.524713,75.503806 89.549784,66.963359"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-6"
|
||||
d="m 56.761123,67.664132 9.82824,7.574867"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81442791;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="m 70.587491,66.948946 18.977538,8.603257"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer26"
|
||||
inkscape:label="StackOverflow-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="StackOverflow-Error"
|
||||
inkscape:label="#g3446"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(1.0098947,0,0,0.9498994,-0.68444657,3.4889072)"
|
||||
inkscape:label="#g4474">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-0"
|
||||
d="m 45.020244,75.290833 9.74566,-7.613709"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.80511868;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 49.577304,75.608168 68.400595,67.02704"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-2"
|
||||
d="m 45.015735,67.662945 9.78324,7.565398"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.81205326;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 49.568595,67.011059 68.46447,75.537737"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer25"
|
||||
inkscape:label="CPUOverload-Error"
|
||||
style="display:inline">
|
||||
style="display:none">
|
||||
<g
|
||||
id="CPUOverload-Error"
|
||||
inkscape:label="#g3438"
|
||||
transform="translate(14,0)">
|
||||
transform="matrix(1,0,0,0.94690781,0,3.7499736)"
|
||||
inkscape:label="#g4486">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-2"
|
||||
d="m 21.425298,75.227504 9.844871,-7.557269"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.8062014;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 91.332053,75.577785 110.51399,66.934663"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6233-9-8"
|
||||
d="M 21.451681,67.664449 31.2556,75.243937"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:0.8136676;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
d="M 91.383458,66.928045 110.4856,75.596579"
|
||||
style="fill:#ff0000;stroke:#ff0000;stroke-width:1.41732287;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -2424,524 +2401,495 @@
|
||||
inkscape:groupmode="layer">
|
||||
<rect
|
||||
inkscape:label="#rect3054"
|
||||
style="fill:none;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
style="fill:none;stroke:#000000;stroke-width:1.09511685;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="rect4795"
|
||||
width="95.066467"
|
||||
height="79.056633"
|
||||
x="0.25920519"
|
||||
y="0.25921404"
|
||||
ry="1" />
|
||||
width="112.74295"
|
||||
height="78.96769"
|
||||
x="0.30367571"
|
||||
y="0.30368456"
|
||||
ry="0.99887496" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="67.606667"
|
||||
y="8.3444462"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="78.238228"
|
||||
y="9.280242"
|
||||
id="text5330-7"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4289"
|
||||
x="67.606667"
|
||||
y="8.3444462">PATH</tspan></text>
|
||||
x="78.238228"
|
||||
y="9.280242">PATH</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="93.860985"
|
||||
y="8.3444462"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="108.69147"
|
||||
y="9.2802429"
|
||||
id="text5330-7-2"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4291"
|
||||
x="93.860985"
|
||||
y="8.3444462">PLAN</tspan></text>
|
||||
x="108.69147"
|
||||
y="9.2802429">PLAN</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="10.759087"
|
||||
y="8.3200321"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="15.664986"
|
||||
y="9.2802429"
|
||||
id="text5330-7-7"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3458"
|
||||
x="10.759087"
|
||||
y="8.3200321">ATTITUDE</tspan></text>
|
||||
id="tspan5813"
|
||||
x="15.664986"
|
||||
y="9.2802429">ATTI</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="41.377663"
|
||||
y="8.3434696"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="46.510185"
|
||||
y="9.2787771"
|
||||
id="text5330-7-3"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4287"
|
||||
x="41.377663"
|
||||
y="8.3434696">STAB</tspan></text>
|
||||
x="46.510185"
|
||||
y="9.2787771">STAB</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="16.329399"
|
||||
y="20.115072"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="16.553135"
|
||||
y="21.460487"
|
||||
id="text5330-7-7-9"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5866"
|
||||
x="16.329399"
|
||||
y="20.115072">GPS</tspan></text>
|
||||
x="16.553135"
|
||||
y="21.460487">GPS</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="37.037819"
|
||||
y="20.115072"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="41.87249"
|
||||
y="21.460487"
|
||||
id="text5330-7-7-6"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4319"
|
||||
x="37.037819"
|
||||
y="20.115072">SENSORS</tspan></text>
|
||||
id="tspan5858"
|
||||
x="41.87249"
|
||||
y="21.460487">SENSOR</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="62.913303"
|
||||
y="20.115072"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="75.206001"
|
||||
y="21.460487"
|
||||
id="text5330-7-7-0"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4321"
|
||||
x="62.913303"
|
||||
y="20.115072">AIRSPEED</tspan></text>
|
||||
id="tspan5860"
|
||||
x="75.206001"
|
||||
y="21.460487">AIRSPD</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="94.605125"
|
||||
y="20.116049"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="110.314"
|
||||
y="21.461952"
|
||||
id="text5330-7-7-8"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3835"
|
||||
x="94.605125"
|
||||
y="20.116049">MAG</tspan></text>
|
||||
x="110.314"
|
||||
y="21.461952">MAG</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="47.086681"
|
||||
y="58.514309"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="118.93848"
|
||||
y="59.436008"
|
||||
id="text5330-0"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.8038279,1.2440474)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5951"
|
||||
x="47.086681"
|
||||
y="58.514309">CPU</tspan></text>
|
||||
x="118.93848"
|
||||
y="59.436008">CPU</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="89.03878"
|
||||
y="58.514309"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="88.885544"
|
||||
y="59.436008"
|
||||
id="text5330-0-4"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.8038279,1.2440474)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4311"
|
||||
x="89.03878"
|
||||
y="58.514309">EVENT</tspan></text>
|
||||
id="tspan5907"
|
||||
x="88.885544"
|
||||
y="59.436008">EVENT</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="60.922539"
|
||||
y="58.514309"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="39.798244"
|
||||
y="59.436008"
|
||||
id="text5330-0-6"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.8038279,1.2440474)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3462"
|
||||
x="60.922539"
|
||||
y="58.514309">MEM.</tspan></text>
|
||||
id="tspan3865"
|
||||
x="39.798244"
|
||||
y="59.436008">MEM</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="74.263214"
|
||||
y="58.513577"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="62.485939"
|
||||
y="59.434544"
|
||||
id="text5330-0-0"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.8038279,1.2440474)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4309"
|
||||
x="74.263214"
|
||||
y="58.513577">STACK</tspan></text>
|
||||
id="tspan5905"
|
||||
x="62.485939"
|
||||
y="59.434544">STACK</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:3px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="106.74649"
|
||||
y="58.476372"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="74.377625"
|
||||
y="36.536701"
|
||||
id="text5330-0-00"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.8038279,1.2440474)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan5947"
|
||||
x="106.74649"
|
||||
y="58.476372">I2C</tspan></text>
|
||||
x="74.377625"
|
||||
y="36.536701">I2C</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="43.342724"
|
||||
y="37.561607"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="68.291183"
|
||||
y="49.551472"
|
||||
id="textconf"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"
|
||||
inkscape:label="#text5330-7-7-9-1"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4317"
|
||||
x="43.342724"
|
||||
y="37.561607">CONF.</tspan></text>
|
||||
id="tspan5978"
|
||||
x="68.291183"
|
||||
y="49.551472">CONFIG</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="61.386131"
|
||||
y="37.561607"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="11.171983"
|
||||
y="61.392075"
|
||||
id="text5858"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"
|
||||
inkscape:label="#text5330-7-7-9-8"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4313"
|
||||
x="61.386131"
|
||||
y="37.561607">BOOT</tspan></text>
|
||||
id="tspan5864"
|
||||
x="11.171983"
|
||||
y="61.392075">BOOT</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="45.628952"
|
||||
y="49.196098"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="94.109077"
|
||||
y="37.710892"
|
||||
id="text5330-7-7-9-8-3"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4315"
|
||||
x="45.628952"
|
||||
y="49.196098">TELEM.</tspan></text>
|
||||
id="tspan5862"
|
||||
x="94.109077"
|
||||
y="37.710892">TELEMETRY</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="75.682053"
|
||||
y="49.196095"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="11.343655"
|
||||
y="49.551472"
|
||||
id="text5330-7-7-9-8-4"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4303"
|
||||
x="75.682053"
|
||||
y="49.196095">BATT.</tspan></text>
|
||||
id="tspan4077"
|
||||
x="11.343655"
|
||||
y="49.551472">BATT</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="96.951797"
|
||||
y="49.196095"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="36.921585"
|
||||
y="49.551472"
|
||||
id="text5330-7-7-9-8-0"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
transform="scale(0.83127393,1.2029729)"
|
||||
inkscape:transform-center-x="-3.0319646"
|
||||
inkscape:transform-center-y="-0.94748894"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan4305"
|
||||
x="96.951797"
|
||||
y="49.196095">TIME</tspan></text>
|
||||
<rect
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.53149605;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="Actuator-7"
|
||||
width="11.450287"
|
||||
height="44.10326"
|
||||
x="71.210968"
|
||||
y="84.344215"
|
||||
ry="1"
|
||||
inkscape:label="#rect4550-4" />
|
||||
x="36.921585"
|
||||
y="49.551472">TIME</tspan></text>
|
||||
<rect
|
||||
inkscape:label="#rect4550-8"
|
||||
ry="1"
|
||||
y="67.18853"
|
||||
x="35.122761"
|
||||
height="8.5405388"
|
||||
width="10.470912"
|
||||
ry="1.1183628"
|
||||
y="66.493958"
|
||||
x="7.053793"
|
||||
height="9.5514212"
|
||||
width="19.134621"
|
||||
id="rect4780"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-7"
|
||||
ry="1"
|
||||
y="67.18853"
|
||||
x="46.889668"
|
||||
height="8.5405388"
|
||||
width="10.470912"
|
||||
id="rect4782"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1"
|
||||
ry="1"
|
||||
y="67.18853"
|
||||
x="58.656513"
|
||||
height="8.5405388"
|
||||
width="10.470912"
|
||||
id="rect4784"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-15"
|
||||
ry="1"
|
||||
y="67.18853"
|
||||
x="70.423416"
|
||||
height="8.5405388"
|
||||
width="10.470912"
|
||||
id="rect4786"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-2"
|
||||
ry="1"
|
||||
y="67.18853"
|
||||
x="82.190269"
|
||||
height="8.5405388"
|
||||
width="10.470912"
|
||||
id="rect4788"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.45410183;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-8"
|
||||
ry="1"
|
||||
y="38.309322"
|
||||
x="49.262897"
|
||||
height="10.308098"
|
||||
width="13.310432"
|
||||
id="rect4790"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
ry="1"
|
||||
y="38.309322"
|
||||
x="64.013565"
|
||||
height="10.308098"
|
||||
width="13.310432"
|
||||
id="rect4792"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
ry="1"
|
||||
y="38.242306"
|
||||
x="78.764183"
|
||||
height="10.308098"
|
||||
width="13.310432"
|
||||
id="rect4794"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="1"
|
||||
y="52.326412"
|
||||
x="76.795616"
|
||||
height="10.265867"
|
||||
width="15.447426"
|
||||
id="rect4796"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.60470587;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5"
|
||||
ry="1"
|
||||
y="52.358059"
|
||||
x="34.470295"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4798"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="1"
|
||||
y="347.495"
|
||||
x="505.26666"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
ry="0.99234092"
|
||||
y="3.5183218"
|
||||
x="7.1022706"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-3"
|
||||
ry="1"
|
||||
y="347.495"
|
||||
x="527.08551"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4802"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-1"
|
||||
ry="1"
|
||||
y="347.495"
|
||||
x="548.90442"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4804"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-2"
|
||||
ry="1"
|
||||
y="347.495"
|
||||
x="570.72327"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4806"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1"
|
||||
y="361.65591"
|
||||
x="505.26666"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4808"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
transform="translate(-497.66563,-344.28037)" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-41"
|
||||
ry="1"
|
||||
y="361.65591"
|
||||
x="527.08551"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4810"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
inkscape:label="#rect4550-8-1-4-21-5-13"
|
||||
ry="1"
|
||||
y="361.65591"
|
||||
x="548.90442"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4812"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
transform="translate(-497.66563,-344.28037)"
|
||||
ry="1"
|
||||
y="361.65591"
|
||||
x="570.72327"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4814"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9-8"
|
||||
ry="1"
|
||||
y="52.326412"
|
||||
x="60.093647"
|
||||
height="10.265867"
|
||||
width="15.447426"
|
||||
id="rect4816"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.60470587;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
ry="1"
|
||||
y="38.309322"
|
||||
x="34.512287"
|
||||
height="10.308098"
|
||||
width="13.310432"
|
||||
id="rect4818"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.56247556;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-4"
|
||||
ry="1"
|
||||
y="84.344215"
|
||||
x="71.210968"
|
||||
height="44.10326"
|
||||
width="11.450287"
|
||||
id="rect4841"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.53149605;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1"
|
||||
y="38.420193"
|
||||
x="7.6010327"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4808-4"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="14.453424"
|
||||
y="37.585503"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="13.357648"
|
||||
y="37.674271"
|
||||
id="text5330-7-7-9-8"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3410"
|
||||
x="14.453424"
|
||||
y="37.585503">INPUT</tspan></text>
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1"
|
||||
y="52.358059"
|
||||
x="7.6010327"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4808-4-4"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-33"
|
||||
ry="1"
|
||||
y="66.372726"
|
||||
x="7.6010327"
|
||||
height="10.202584"
|
||||
width="18.966711"
|
||||
id="rect4808-4-4-7"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.66798913;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
id="tspan5909"
|
||||
x="13.357648"
|
||||
y="37.674271">INPUT</tspan></text>
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:4px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="12.280572"
|
||||
y="49.196102"
|
||||
style="font-size:6px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
x="40.654816"
|
||||
y="37.710892"
|
||||
id="text5330-7-7-9-8-1"
|
||||
sodipodi:linespacing="125%"
|
||||
transform="scale(0.83127393,1.2029729)"><tspan
|
||||
sodipodi:role="line"
|
||||
id="tspan3412"
|
||||
x="12.280572"
|
||||
y="49.196102">OUTPUT</tspan></text>
|
||||
id="tspan5911"
|
||||
x="40.654816"
|
||||
y="37.710892">OUTPUT</tspan></text>
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.98703158"
|
||||
y="51.95937"
|
||||
x="54.784607"
|
||||
height="10.132735"
|
||||
width="23.300135"
|
||||
id="rect4796-2-7"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.99532819"
|
||||
y="51.916786"
|
||||
x="7.1737313"
|
||||
height="10.217907"
|
||||
width="18.079369"
|
||||
id="rect4796-2-79"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.99532819"
|
||||
y="51.916786"
|
||||
x="27.540998"
|
||||
height="10.217907"
|
||||
width="18.079369"
|
||||
id="rect4796-2-3"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.98714912"
|
||||
y="37.71487"
|
||||
x="32.498486"
|
||||
height="10.133942"
|
||||
width="23.221214"
|
||||
id="rect4796-2-79-9"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="1.0086432"
|
||||
y="37.604546"
|
||||
x="57.889503"
|
||||
height="10.354595"
|
||||
width="11.382303"
|
||||
id="rect4796-2-79-8"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.97385728"
|
||||
y="37.783096"
|
||||
x="77.012535"
|
||||
height="9.9974899"
|
||||
width="33.066151"
|
||||
id="rect4796-2-79-8-6"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="3.5183218"
|
||||
x="33.500103"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-2"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="3.5183218"
|
||||
x="59.897934"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-4"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="3.5183218"
|
||||
x="86.295769"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-8"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="18.172588"
|
||||
x="7.1022706"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-6"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="18.172588"
|
||||
x="33.500103"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-5"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="18.172588"
|
||||
x="59.897934"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-5-4"
|
||||
ry="0.99234092"
|
||||
y="18.172588"
|
||||
x="86.295769"
|
||||
height="10.124442"
|
||||
width="23.84639"
|
||||
id="rect4800-9"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8"
|
||||
ry="1.1183628"
|
||||
y="66.493958"
|
||||
x="28.054348"
|
||||
height="9.5514212"
|
||||
width="19.134621"
|
||||
id="rect4780-0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8"
|
||||
ry="1.1183628"
|
||||
y="66.493958"
|
||||
x="49.054901"
|
||||
height="9.5514212"
|
||||
width="19.134621"
|
||||
id="rect4780-06"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8"
|
||||
ry="1.1183628"
|
||||
y="66.493958"
|
||||
x="70.05545"
|
||||
height="9.5514212"
|
||||
width="19.134621"
|
||||
id="rect4780-1"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8"
|
||||
ry="1.1183628"
|
||||
y="66.493958"
|
||||
x="91.056015"
|
||||
height="9.5514212"
|
||||
width="19.134621"
|
||||
id="rect4780-3"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="0.98714912"
|
||||
y="37.71487"
|
||||
x="7.0977092"
|
||||
height="10.133942"
|
||||
width="23.221214"
|
||||
id="rect4796-2-79-9-3"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="1.0036905"
|
||||
y="51.873863"
|
||||
x="80.600296"
|
||||
height="10.303754"
|
||||
width="13.522519"
|
||||
id="rect4796-2-7-4"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<rect
|
||||
inkscape:label="#rect4550-8-1-4-21-2-9"
|
||||
ry="1.0036905"
|
||||
y="51.873863"
|
||||
x="96.638374"
|
||||
height="10.303754"
|
||||
width="13.522519"
|
||||
id="rect4796-2-7-4-0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.70866144;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer36"
|
||||
inkscape:label="No Link"
|
||||
style="display:none">
|
||||
style="display:inline">
|
||||
<g
|
||||
id="nolink"
|
||||
inkscape:label="#g4324">
|
||||
inkscape:label="#g4534">
|
||||
<rect
|
||||
inkscape:label="#nolink"
|
||||
style="opacity:0.51388891;fill:#483737;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.00617588;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
style="opacity:0.51388891;fill:#483737;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:1.09553051;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
id="opacity"
|
||||
width="95.066467"
|
||||
width="112.70118"
|
||||
height="79.056633"
|
||||
x="0.25920519"
|
||||
x="0.27291748"
|
||||
y="0.2592113"
|
||||
ry="1.6285406" />
|
||||
<rect
|
||||
ry="2.3865318"
|
||||
y="29.358137"
|
||||
x="18.381285"
|
||||
x="19.781004"
|
||||
height="7.3904138"
|
||||
width="62.155273"
|
||||
width="73.685005"
|
||||
id="rect8557"
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:#800000;stroke-width:0.53149605;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:#800000;stroke-width:0.57869613;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<text
|
||||
transform="scale(1.0128485,0.98731448)"
|
||||
transform="scale(1.1027957,0.90678628)"
|
||||
sodipodi:linespacing="125%"
|
||||
id="text8563"
|
||||
y="36.071426"
|
||||
x="33.608711"
|
||||
style="font-size:7.27633667px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#800000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
y="39.286636"
|
||||
x="34.689133"
|
||||
style="font-size:7.92252016px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#800000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Arial Bold"
|
||||
xml:space="preserve"><tspan
|
||||
y="36.071426"
|
||||
x="33.608711"
|
||||
y="39.286636"
|
||||
x="34.689133"
|
||||
id="tspan8565"
|
||||
sodipodi:role="line">NO LINK</tspan></text>
|
||||
<g
|
||||
transform="matrix(1.0659619,0,0,1.2030901,11.890962,-5.4421624)"
|
||||
transform="matrix(1.2636966,0,0,1.2030901,13.594698,-5.5358311)"
|
||||
id="g4267">
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:0.29055119;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
@ -2961,7 +2909,7 @@
|
||||
sodipodi:cy="35.07505"
|
||||
sodipodi:rx="0.5"
|
||||
sodipodi:ry="0.5"
|
||||
d="m 14,35.07505 c 0,0.276143 -0.223858,0.5 -0.5,0.5 -0.276142,0 -0.5,-0.223857 -0.5,-0.5 0,-0.276142 0.223858,-0.5 0.5,-0.5 0.269688,0 0.490781,0.21388 0.499725,0.483419"
|
||||
d="m 14,35.07505 a 0.5,0.5 0 1 1 -2.75e-4,-0.01658"
|
||||
sodipodi:start="0"
|
||||
sodipodi:end="6.2500167"
|
||||
sodipodi:open="true"
|
||||
@ -2973,7 +2921,7 @@
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
transform="matrix(1.0659619,0,0,1.2030901,59.303858,-5.5104487)"
|
||||
transform="matrix(1.2636966,0,0,1.2030901,66.606704,-5.5358311)"
|
||||
id="g4267-4"
|
||||
style="display:inline">
|
||||
<path
|
||||
@ -2994,7 +2942,7 @@
|
||||
sodipodi:cy="35.07505"
|
||||
sodipodi:rx="0.5"
|
||||
sodipodi:ry="0.5"
|
||||
d="m 14,35.07505 c 0,0.276143 -0.223858,0.5 -0.5,0.5 -0.276142,0 -0.5,-0.223857 -0.5,-0.5 0,-0.276142 0.223858,-0.5 0.5,-0.5 0.269688,0 0.490781,0.21388 0.499725,0.483419"
|
||||
d="m 14,35.07505 a 0.5,0.5 0 1 1 -2.75e-4,-0.01658"
|
||||
sodipodi:start="0"
|
||||
sodipodi:end="6.2500167"
|
||||
sodipodi:open="true"
|
||||
|
Before Width: | Height: | Size: 105 KiB After Width: | Height: | Size: 104 KiB |
@ -10,6 +10,27 @@ Item {
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: batinfo_energy
|
||||
elementName: "warning-low-energy"
|
||||
sceneSize: info.sceneSize
|
||||
Rectangle {
|
||||
anchors.fill: batinfo_energy
|
||||
border.width: 0
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": "black"))
|
||||
|
||||
visible: FlightBatteryState.ConsumedEnergy > 0
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: energy_label
|
||||
elementName: "battery-milliamp-label"
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
|
||||
Repeater {
|
||||
id: satNumberBar
|
||||
|
||||
@ -31,10 +52,136 @@ Item {
|
||||
|
||||
Text {
|
||||
text: ["No GPS", "No Fix", "Fix2D", "Fix3D"][GPSPositionSensor.Status]
|
||||
anchors.centerIn: parent
|
||||
font.pixelSize: parent.height*1.2
|
||||
color: "white"
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
sceneSize: info.sceneSize
|
||||
elementName: "telemetry-status"
|
||||
|
||||
Text {
|
||||
text: ["Disconnected","HandshakeReq","HandshakeAck","Connected"][GCSTelemetryStats.Status]
|
||||
|
||||
anchors.centerIn: parent
|
||||
font.pixelSize: parent.height*1.2
|
||||
color: "white"
|
||||
}
|
||||
}
|
||||
|
||||
Repeater {
|
||||
id: txNumberBar
|
||||
|
||||
property int txRateNumber : GCSTelemetryStats.TxDataRate.toFixed()/10 // 250 max
|
||||
|
||||
model: 25
|
||||
SvgElementImage {
|
||||
property int minTxRateNumber : index+1
|
||||
elementName: "tx" + minTxRateNumber
|
||||
sceneSize: info.sceneSize
|
||||
visible: txNumberBar.txRateNumber >= minTxRateNumber
|
||||
}
|
||||
}
|
||||
|
||||
Repeater {
|
||||
id: rxNumberBar
|
||||
|
||||
property int rxRateNumber : GCSTelemetryStats.RxDataRate.toFixed()/100 // 2500 max
|
||||
|
||||
model: 25
|
||||
SvgElementImage {
|
||||
property int minRxRateNumber : index+1
|
||||
elementName: "rx" + minRxRateNumber
|
||||
sceneSize: info.sceneSize
|
||||
visible: rxNumberBar.rxRateNumber >= minRxRateNumber
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
sceneSize: info.sceneSize
|
||||
elementName: "battery-volt-text"
|
||||
visible: FlightBatteryState.Voltage > 0
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Voltage.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
family: "Arial"
|
||||
pixelSize: parent.height * 1.3
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
sceneSize: info.sceneSize
|
||||
elementName: "battery-amp-text"
|
||||
visible: FlightBatteryState.Current > 0
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.Current.toFixed(2)
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
family: "Arial"
|
||||
pixelSize: parent.height * 1.3
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementPositionItem {
|
||||
sceneSize: info.sceneSize
|
||||
elementName: "battery-milliamp-text"
|
||||
visible: FlightBatteryState.ConsumedEnergy > 0
|
||||
|
||||
Text {
|
||||
text: FlightBatteryState.ConsumedEnergy.toFixed()
|
||||
anchors.centerIn: parent
|
||||
color: "white"
|
||||
font {
|
||||
family: "Arial"
|
||||
pixelSize: parent.height * 1.3
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Repeater {
|
||||
id: throttleNumberBar
|
||||
|
||||
property int throttleNumber : ActuatorDesired.Thrust.toFixed(1)*10
|
||||
|
||||
model: 10
|
||||
SvgElementImage {
|
||||
property int minThrottleNumber : index+1
|
||||
elementName: "eng" + minThrottleNumber
|
||||
sceneSize: info.sceneSize
|
||||
visible: throttleNumberBar.throttleNumber >= minThrottleNumber
|
||||
}
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: mask_ThrottleBar
|
||||
elementName: "throttle-mask"
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: mask_SatBar
|
||||
elementName: "satbar-mask"
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: mask_telemetryTx
|
||||
elementName: "tx-mask"
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: mask_telemetryRx
|
||||
elementName: "rx-mask"
|
||||
sceneSize: info.sceneSize
|
||||
}
|
||||
}
|
||||
|
@ -47,9 +47,17 @@ Rectangle {
|
||||
anchors.centerIn: parent
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: side_slip_fixed
|
||||
elementName: "sideslip-fixed"
|
||||
sceneSize: sceneItem.viewportSize
|
||||
|
||||
x: scaledBounds.x * sceneItem.width
|
||||
}
|
||||
|
||||
SvgElementImage {
|
||||
id: side_slip
|
||||
elementName: "sideslip"
|
||||
elementName: "sideslip-moving"
|
||||
sceneSize: sceneItem.viewportSize
|
||||
smooth: true
|
||||
|
||||
@ -65,7 +73,7 @@ Rectangle {
|
||||
|
||||
anchors.horizontalCenter: foreground.horizontalCenter
|
||||
//0.5 coefficient is empirical to limit indicator movement
|
||||
anchors.horizontalCenterOffset: -sideSlip*width*0.5
|
||||
anchors.horizontalCenterOffset: sideSlip*width*0.1 //was 0.5
|
||||
y: scaledBounds.y * sceneItem.height
|
||||
}
|
||||
|
||||
@ -89,11 +97,6 @@ Rectangle {
|
||||
sceneSize: sceneItem.viewportSize
|
||||
}
|
||||
|
||||
PfdIndicators {
|
||||
anchors.fill: parent
|
||||
sceneSize: sceneItem.viewportSize
|
||||
}
|
||||
|
||||
Info {
|
||||
anchors.fill: parent
|
||||
sceneSize: sceneItem.viewportSize
|
||||
|
@ -41,9 +41,8 @@ Item {
|
||||
|
||||
SvgElementImage {
|
||||
id: horizont_line
|
||||
//elementName: "world-centerline"
|
||||
// TODO: rename the centerline element in svg file
|
||||
elementName: "path4731"
|
||||
elementName: "center-line"
|
||||
|
||||
//worldView is loaded with Loader, so background element is visible
|
||||
sceneSize: background.sceneSize
|
||||
anchors.centerIn: parent
|
||||
|
@ -21,8 +21,9 @@ Item {
|
||||
//rotate it around the center of horizon
|
||||
transform: Rotation {
|
||||
angle: -AttitudeState.Roll
|
||||
origin.y : sceneItem.horizontCenter - rollscale.height/2
|
||||
origin.y : rollscale.height*2.4
|
||||
origin.x : rollscale.width/2
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -13,13 +13,44 @@
|
||||
height="480"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.2 r9819"
|
||||
sodipodi:docname="pfd-2.svg"
|
||||
inkscape:version="0.48.4 r9939"
|
||||
sodipodi:docname="pfd.svg"
|
||||
inkscape:export-filename="/Users/muralha/Desktop/new PFD ideas/pfd/test2.png"
|
||||
inkscape:export-xdpi="72"
|
||||
inkscape:export-ydpi="72">
|
||||
<defs
|
||||
id="defs4" />
|
||||
id="defs4">
|
||||
<linearGradient
|
||||
id="linearGradient4619">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:0;"
|
||||
offset="0"
|
||||
id="stop4621" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:0.35294119;"
|
||||
offset="1"
|
||||
id="stop4623" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5006">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:0;"
|
||||
offset="0"
|
||||
id="stop5008" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:0.17985612;"
|
||||
offset="1"
|
||||
id="stop5010" />
|
||||
</linearGradient>
|
||||
<filter
|
||||
inkscape:collect="always"
|
||||
id="filter4991">
|
||||
<feGaussianBlur
|
||||
inkscape:collect="always"
|
||||
stdDeviation="125.9375"
|
||||
id="feGaussianBlur4993" />
|
||||
</filter>
|
||||
</defs>
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
pagecolor="#ffffff"
|
||||
@ -27,26 +58,36 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="1.575"
|
||||
inkscape:zoom="1.3234375"
|
||||
inkscape:cx="320"
|
||||
inkscape:cy="240"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="svg2"
|
||||
inkscape:current-layer="layer2"
|
||||
showgrid="false"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0"
|
||||
inkscape:window-width="1920"
|
||||
inkscape:window-height="944"
|
||||
inkscape:window-x="1280"
|
||||
inkscape:window-y="0"
|
||||
inkscape:window-maximized="0"
|
||||
showguides="false"
|
||||
inkscape:guide-bbox="true">
|
||||
inkscape:window-width="1280"
|
||||
inkscape:window-height="928"
|
||||
inkscape:window-x="0"
|
||||
inkscape:window-y="27"
|
||||
inkscape:window-maximized="1"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true"
|
||||
inkscape:object-nodes="true"
|
||||
inkscape:object-paths="true"
|
||||
inkscape:snap-bbox="false"
|
||||
inkscape:bbox-nodes="false"
|
||||
inkscape:snap-bbox-midpoints="false"
|
||||
inkscape:snap-grids="true"
|
||||
inkscape:snap-to-guides="true"
|
||||
inkscape:snap-nodes="true"
|
||||
inkscape:bbox-paths="false"
|
||||
inkscape:snap-global="true">
|
||||
<sodipodi:guide
|
||||
orientation="1,0"
|
||||
position="320,275.14994"
|
||||
position="320.03652,382.998"
|
||||
id="guide4799" />
|
||||
<sodipodi:guide
|
||||
orientation="0,1"
|
||||
@ -64,6 +105,13 @@
|
||||
orientation="0,1"
|
||||
position="328.00768,112"
|
||||
id="guide8892" />
|
||||
<inkscape:grid
|
||||
type="xygrid"
|
||||
id="grid4721"
|
||||
empspacing="1"
|
||||
visible="true"
|
||||
enabled="true"
|
||||
snapvisiblegridlinesonly="true" />
|
||||
</sodipodi:namedview>
|
||||
<metadata
|
||||
id="metadata7">
|
||||
@ -87,7 +135,7 @@
|
||||
<g
|
||||
id="horizon"
|
||||
inkscape:label="#g4445"
|
||||
transform="translate(0,10)">
|
||||
transform="translate(1,51.918684)">
|
||||
<rect
|
||||
y="-669"
|
||||
x="-819"
|
||||
@ -106,9 +154,14 @@
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4731"
|
||||
d="m -163.61586,169.00008 970.78709,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2.99985003;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
id="center-line"
|
||||
d="m -179.5,169.08132 997,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="pitch0"
|
||||
d="m 266,169.08132 106,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:6;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -122,26 +175,27 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer16"
|
||||
inkscape:label="pitch-window"
|
||||
style="display:none"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:none;stroke:#ff0000;stroke-width:1.00041986;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0"
|
||||
id="pitch-window"
|
||||
width="118.99958"
|
||||
height="178.99957"
|
||||
x="260.5304"
|
||||
y="89.470001"
|
||||
width="119"
|
||||
height="179"
|
||||
x="260.5"
|
||||
y="131.5"
|
||||
inkscape:label="#rect6180" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer15"
|
||||
inkscape:label="pitch-scale"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="pitch-scale"
|
||||
inkscape:label="#g8154"
|
||||
transform="translate(0,10)">
|
||||
transform="translate(0,52)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6182"
|
||||
@ -836,12 +890,6 @@
|
||||
id="path6626"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="pitch0"
|
||||
d="m 266.79725,169 105.93443,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
inkscape:label="#path6754" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
@ -962,7 +1010,9 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer26"
|
||||
inkscape:label="home-eta-text">
|
||||
inkscape:label="home-eta-text"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#00ffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="home-eta-text">
|
||||
@ -1012,7 +1062,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer27"
|
||||
inkscape:label="home-distance-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#00ffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="home-distance-text">
|
||||
@ -1057,7 +1108,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer28"
|
||||
inkscape:label="home-heading-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#00ffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="home-heading-text">
|
||||
@ -1089,46 +1141,56 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer48"
|
||||
inkscape:label="info-bg">
|
||||
inkscape:label="info-bg"
|
||||
style="display:inline"
|
||||
transform="translate(0,4)"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="info-bg"
|
||||
inkscape:label="#g4460">
|
||||
<path
|
||||
style="fill:none;stroke:#c8c8c8;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:0.15686275;stroke-dasharray:none;filter:url(#filter4991)"
|
||||
d="m -5,53.5 650,0"
|
||||
id="path4612"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<rect
|
||||
inkscape:label="#rect4734"
|
||||
y="3.4998488"
|
||||
x="-0.50015116"
|
||||
height="34.000301"
|
||||
width="641.00031"
|
||||
y="-0.5"
|
||||
x="-0.5"
|
||||
height="54"
|
||||
width="641"
|
||||
id="info-bg-top"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#ffffff;stroke-width:0.99969769;display:inline" />
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#ffffff;stroke-width:1;stroke-linejoin:round;stroke-miterlimit:4;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path10158"
|
||||
d="M 181,37 181,4.00177"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="M 180,54 180,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 90,37 90,4.0309479"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 90,54 90,0"
|
||||
id="path10160"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path10162"
|
||||
d="M 459,36.99995 459,4.0000507"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="M 460,54 460,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 550,37 550,4.0309479"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 550,54 550,0"
|
||||
id="path10164"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path10166"
|
||||
d="m -0.49190889,20.679943 180.99441889,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.99999988px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="m -0.5,18 180,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="gps-label">
|
||||
id="gps-label"
|
||||
transform="translate(0,-3.01148)">
|
||||
<path
|
||||
d="m 9.5151701,14.066165 0,-1.566406 -1.2890625,0 0,-0.648438 2.0703124,0 0,2.503906 c -0.3046926,0.216147 -0.6406298,0.380209 -1.0078124,0.492188 -0.3671917,0.109375 -0.7591184,0.164062 -1.1757813,0.164062 -0.9114607,0 -1.6250017,-0.265624 -2.140625,-0.796875 C 5.4591798,13.68075 5.2026696,12.938563 5.2026701,11.98804 c -5e-7,-0.953121 0.2565097,-1.695308 0.7695312,-2.2265625 0.5156233,-0.5338485 1.2291643,-0.8007753 2.140625,-0.8007813 0.3802046,6e-6 0.7408814,0.046881 1.0820313,0.140625 0.3437452,0.093756 0.6601511,0.2317764 0.9492184,0.4140625 l 0,0.8398433 C 9.8524046,10.107836 9.5425091,9.9216387 9.2143888,9.7966337 8.8862597,9.6716389 8.541208,9.609139 8.1792326,9.6091337 7.4656882,9.609139 6.9292304,9.8083576 6.5698576,10.20679 c -0.3567723,0.398442 -0.5351575,0.992191 -0.5351563,1.78125 -1.2e-6,0.78646 0.178384,1.378908 0.5351563,1.777344 0.3593728,0.398438 0.8958306,0.597657 1.609375,0.597656 0.2786421,1e-6 0.5273398,-0.02344 0.7460937,-0.07031 0.2187457,-0.04948 0.41536,-0.124999 0.5898438,-0.226562"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1147,7 +1209,8 @@
|
||||
</g>
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="gps-sats-label">
|
||||
id="gps-sats-label"
|
||||
transform="translate(0,6.488519)">
|
||||
<path
|
||||
d="m 9.0347013,26.257572 0,0.769531 C 8.7352182,26.883879 8.4526664,26.777109 8.1870451,26.706791 7.9214169,26.636484 7.6649068,26.601327 7.4175138,26.601322 c -0.4296897,5e-6 -0.7617206,0.08334 -0.9960937,0.25 -0.2317723,0.166672 -0.3476576,0.403651 -0.3476563,0.710938 -1.3e-6,0.257816 0.076822,0.453129 0.2304688,0.585937 0.1562483,0.130212 0.4505188,0.235681 0.8828125,0.316406 l 0.4765625,0.09766 c 0.5885382,0.111982 1.0221315,0.309899 1.3007812,0.59375 0.2812456,0.281252 0.4218704,0.658856 0.421875,1.132812 -4.6e-6,0.565105 -0.1901086,0.99349 -0.5703125,1.285156 -0.3776078,0.291667 -0.9322947,0.4375 -1.6640625,0.4375 -0.2760437,0 -0.5703143,-0.03125 -0.8828125,-0.09375 -0.309897,-0.0625 -0.6315113,-0.154947 -0.9648437,-0.277343 l 0,-0.8125 c 0.3203116,0.179688 0.6341134,0.315105 0.9414062,0.40625 0.3072899,0.09115 0.6093729,0.136719 0.90625,0.136718 0.450518,1e-6 0.7981739,-0.08854 1.0429688,-0.265625 0.244788,-0.177082 0.3671837,-0.429686 0.3671875,-0.757812 -3.8e-6,-0.286457 -0.088545,-0.510415 -0.265625,-0.671875 C 8.1219376,29.514085 7.8341774,29.392991 7.4331388,29.31226 L 6.9526701,29.21851 C 6.3641268,29.101325 5.938346,28.917731 5.6753263,28.667728 5.4123049,28.417732 5.2807946,28.070076 5.2807951,27.62476 c -5e-7,-0.515621 0.1809889,-0.92187 0.5429687,-1.21875 0.3645819,-0.29687 0.8658835,-0.445307 1.5039063,-0.445313 0.2734346,6e-6 0.5520802,0.02475 0.8359375,0.07422 0.2838505,0.04949 0.5742148,0.123704 0.8710937,0.222656"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1171,7 +1234,8 @@
|
||||
</g>
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="telemetry-tx-label">
|
||||
id="telemetry-tx-label"
|
||||
transform="translate(0,-3.08992)">
|
||||
<path
|
||||
d="m 96.455605,9.2578888 4.933595,0 0,0.6640625 -2.070314,0 0,5.1679687 -0.792969,0 0,-5.1679687 -2.070312,0 0,-0.6640625"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1185,7 +1249,8 @@
|
||||
</g>
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="telemetry-rx-label">
|
||||
id="telemetry-rx-label"
|
||||
transform="translate(0,-2.08992)">
|
||||
<path
|
||||
d="m 100.02982,29.355545 c 0.16927,0.05729 0.33333,0.17969 0.49219,0.367188 0.16145,0.187502 0.32291,0.445314 0.48438,0.773437 l 0.80078,1.59375 -0.84766,0 -0.74609,-1.496094 c -0.19271,-0.390623 -0.380215,-0.649737 -0.562503,-0.777343 -0.17969,-0.127602 -0.425784,-0.191404 -0.738281,-0.191407 l -0.859375,0 0,2.464844 -0.789063,0 0,-5.832031 1.78125,0 c 0.666664,6e-6 1.164062,0.139328 1.492192,0.417969 0.32812,0.278651 0.49218,0.699223 0.49218,1.261718 0,0.367192 -0.0859,0.671879 -0.25781,0.914063 -0.16927,0.24219 -0.41667,0.410159 -0.74219,0.503906 m -1.976559,-2.449219 0,2.070313 0.992187,0 c 0.380206,3e-6 0.666664,-0.08724 0.859375,-0.261719 0.195307,-0.17708 0.292967,-0.436194 0.292967,-0.777344 0,-0.341141 -0.0977,-0.597651 -0.292967,-0.769531 -0.192711,-0.174474 -0.479169,-0.261714 -0.859375,-0.261719 l -0.992187,0"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1197,9 +1262,35 @@
|
||||
id="path6310"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="info-battery"
|
||||
inkscape:label="#g3816">
|
||||
<rect
|
||||
y="0"
|
||||
x="551"
|
||||
height="17"
|
||||
width="89"
|
||||
id="warning-low-voltage"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none" />
|
||||
<rect
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="warning-high-current"
|
||||
width="89"
|
||||
height="17"
|
||||
x="551"
|
||||
y="18" />
|
||||
<rect
|
||||
y="35.5"
|
||||
x="551"
|
||||
height="17"
|
||||
width="89"
|
||||
id="warning-low-energy"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none" />
|
||||
</g>
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="throttle-label">
|
||||
id="throttle-label"
|
||||
transform="translate(0,-3.203204)">
|
||||
<path
|
||||
d="m 489.4556,9.2578888 4.93359,0 0,0.6640625 -2.07031,0 0,5.1679687 -0.79297,0 0,-5.1679687 -2.07031,0 0,-0.6640625"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1241,46 +1332,47 @@
|
||||
id="path6472"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<g
|
||||
id="warning-low-battery"
|
||||
inkscape:label="#g3816">
|
||||
<rect
|
||||
y="4"
|
||||
x="551"
|
||||
height="16"
|
||||
width="89"
|
||||
id="rect3812"
|
||||
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:none" />
|
||||
<rect
|
||||
style="fill:#ff0000;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="rect3814"
|
||||
width="89"
|
||||
height="16"
|
||||
x="551"
|
||||
y="21" />
|
||||
</g>
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="battery-milliamp-label">
|
||||
id="battery-milliamp-label"
|
||||
transform="matrix(1,0,0,1.0375514,-2,-6.9526728)">
|
||||
<path
|
||||
d="m 625.63916,28.554764 c 0.17968,-0.322913 0.39453,-0.561194 0.64453,-0.714844 0.25,-0.153641 0.54427,-0.230464 0.88281,-0.230469 0.45573,5e-6 0.80729,0.160161 1.05469,0.480469 0.24739,0.317712 0.37109,0.770837 0.3711,1.359375 l 0,2.640625 -0.72266,0 0,-2.617187 c -10e-6,-0.419268 -0.0742,-0.730466 -0.22266,-0.933594 -0.14844,-0.203121 -0.375,-0.304684 -0.67968,-0.304688 -0.37241,4e-6 -0.66668,0.123702 -0.88282,0.371094 -0.21615,0.247399 -0.32422,0.584638 -0.32422,1.011719 l 0,2.472656 -0.72265,0 0,-2.617187 c -10e-6,-0.421872 -0.0742,-0.73307 -0.22266,-0.933594 -0.14844,-0.203121 -0.37761,-0.304684 -0.6875,-0.304688 -0.36719,4e-6 -0.65885,0.125004 -0.875,0.375 -0.21615,0.247399 -0.32422,0.583337 -0.32422,1.007813 l 0,2.472656 -0.72265,0 0,-4.375 0.72265,0 0,0.679688 c 0.16406,-0.268226 0.36068,-0.466142 0.58985,-0.59375 0.22916,-0.1276 0.5013,-0.191402 0.8164,-0.191407 0.31771,5e-6 0.58724,0.08073 0.8086,0.242188 0.22395,0.161462 0.38932,0.395837 0.49609,0.703125"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
id="path6812"
|
||||
d="m 620.206,52 0,-4.224819 0.64048,0 0,0.592748 c 0.13261,-0.206861 0.30897,-0.372618 0.5291,-0.497271 0.22012,-0.127298 0.47075,-0.190948 0.75188,-0.190953 0.31294,5e-6 0.56887,0.06498 0.76778,0.194931 0.20156,0.129957 0.34345,0.311627 0.42567,0.545009 0.33416,-0.493289 0.76911,-0.739935 1.30484,-0.73994 0.41903,5e-6 0.74126,0.116698 0.96669,0.350079 0.22543,0.230738 0.33814,0.587447 0.33815,1.070129 l 0,2.900087 -0.71209,0 0,-2.661397 c -10e-6,-0.286425 -0.0239,-0.491964 -0.0716,-0.616617 -0.0451,-0.127298 -0.12863,-0.229404 -0.25063,-0.306319 -0.122,-0.07691 -0.26521,-0.115363 -0.42964,-0.115367 -0.29704,4e-6 -0.54369,0.09946 -0.73994,0.298363 -0.19626,0.19626 -0.29439,0.511861 -0.29438,0.946805 l 0,2.454532 -0.71608,0 0,-2.744939 c 0,-0.31825 -0.0583,-0.55694 -0.17503,-0.716071 -0.1167,-0.159123 -0.30765,-0.238686 -0.57286,-0.23869 -0.20156,4e-6 -0.38854,0.05305 -0.56092,0.159127 -0.16974,0.106088 -0.29306,0.261237 -0.36997,0.465446 -0.0769,0.204216 -0.11537,0.4986 -0.11537,0.883154 l 0,2.191973 -0.71607,0"
|
||||
id="path4641"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 632.01025,27.035233 -1.07031,2.902343 2.14453,0 -1.07422,-2.902343 m -0.44531,-0.777344 0.89453,0 2.22266,5.832031 -0.82031,0 -0.53125,-1.496094 -2.62891,0 -0.53125,1.496094 -0.83203,0 2.22656,-5.832031"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
id="path6814"
|
||||
d="m 632.45877,52 0,-5.832 0.71607,0 0,2.092518 c 0.33416,-0.387204 0.75585,-0.580808 1.26506,-0.580813 0.31294,5e-6 0.58479,0.06233 0.81552,0.186974 0.23073,0.122002 0.39516,0.291737 0.4933,0.509206 0.10077,0.217477 0.15116,0.533079 0.15117,0.946805 l 0,2.67731 -0.71607,0 0,-2.67731 c -10e-6,-0.358032 -0.0782,-0.617939 -0.23472,-0.779721 -0.15382,-0.164428 -0.37262,-0.246643 -0.65639,-0.246647 -0.21218,4e-6 -0.41241,0.0557 -0.60071,0.167083 -0.18565,0.10874 -0.31825,0.257259 -0.39782,0.445555 -0.0796,0.188304 -0.11934,0.44821 -0.11934,0.779722 l 0,2.311318 -0.71607,0"
|
||||
id="path4645"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 626.46764,52 2.23971,-5.832 0.83144,0 2.3869,5.832 -0.87917,0 -0.68027,-1.766308 -2.43862,0 L 627.28714,52 l -0.8195,0 m 1.68277,-2.394859 1.97715,0 -0.60866,-1.615138 c -0.18565,-0.490637 -0.32356,-0.893758 -0.41373,-1.209364 -0.0743,0.373953 -0.17902,0.745248 -0.31428,1.113888 l -0.64048,1.710614"
|
||||
id="path4643"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:0.99999994px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 550.91468,20.679943 89.63711,0"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4588"
|
||||
d="m 550,35.5 90,0"
|
||||
style="fill:none;stroke:#ffffff;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<g
|
||||
id="battery-amp-label"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
transform="matrix(1,0,0,1.0375459,-5.79738,-4.2947649)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4614"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
d="m 632.01025,27.035233 -1.07031,2.902343 2.14453,0 -1.07422,-2.902343 m -0.44531,-0.777344 0.89453,0 2.22266,5.832031 -0.82031,0 -0.53125,-1.496094 -2.62891,0 -0.53125,1.496094 -0.83203,0 2.22656,-5.832031" />
|
||||
</g>
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 550,17.5 90,0"
|
||||
id="path10341"
|
||||
inkscape:connector-curvature="0" />
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="battery-volt-label">
|
||||
id="battery-volt-label"
|
||||
transform="matrix(1,0,0,1.0375459,0,-3.6189387)">
|
||||
<path
|
||||
d="m 625.76807,14.08992 -2.22657,-5.8320312 0.82422,0 1.84766,4.9101562 1.85156,-4.9101562 0.82031,0 -2.22265,5.8320312 -0.89453,0"
|
||||
style="font-size:8px;fill:#ffffff"
|
||||
@ -1392,20 +1484,30 @@
|
||||
id="path6806"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="m 90,36 90,0"
|
||||
id="path5067"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer64"
|
||||
id="g4727"
|
||||
inkscape:label="battery"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer66"
|
||||
inkscape:label="battery-milliamp-text">
|
||||
inkscape:label="battery-milliamp-text"
|
||||
transform="translate(0,1.768481)"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:10px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="battery-milliamp-text">
|
||||
id="battery-milliamp-text"
|
||||
transform="translate(0,17)">
|
||||
<path
|
||||
d="m 572.57764,32.938553 0,-0.898438 c 0.24739,0.117189 0.49804,0.206707 0.75195,0.268555 0.2539,0.06185 0.50293,0.09277 0.74707,0.09277 0.65104,10e-7 1.14746,-0.218098 1.48926,-0.654296 0.34505,-0.439452 0.54199,-1.105141 0.59082,-1.997071 -0.18881,0.279951 -0.42807,0.494795 -0.71778,0.644532 -0.28971,0.149742 -0.61035,0.224611 -0.96191,0.224609 -0.72917,2e-6 -1.30697,-0.219724 -1.7334,-0.65918 -0.42318,-0.442705 -0.63476,-1.046545 -0.63476,-1.811523 0,-0.748692 0.22135,-1.349278 0.66406,-1.801758 0.44271,-0.452467 1.0319,-0.678704 1.76758,-0.678711 0.84309,7e-6 1.486,0.3239 1.92871,0.97168 0.44596,0.644537 0.66894,1.582036 0.66894,2.8125 0,1.149091 -0.27344,2.067059 -0.82031,2.753906 -0.54362,0.683594 -1.27604,1.02539 -2.19726,1.025391 -0.2474,-10e-7 -0.49805,-0.02441 -0.75196,-0.07324 -0.25391,-0.04883 -0.51758,-0.12207 -0.79101,-0.219726 m 1.96289,-3.09082 c 0.4427,3e-6 0.79264,-0.151364 1.0498,-0.454102 0.26041,-0.30273 0.39062,-0.717769 0.39063,-1.245117 -10e-6,-0.524083 -0.13022,-0.937494 -0.39063,-1.240235 -0.25716,-0.305983 -0.6071,-0.458977 -1.0498,-0.458984 -0.44271,7e-6 -0.79428,0.153001 -1.05469,0.458984 -0.25716,0.302741 -0.38574,0.716152 -0.38574,1.240235 0,0.527348 0.12858,0.942387 0.38574,1.245117 0.26041,0.302738 0.61198,0.454105 1.05469,0.454102"
|
||||
style="fill:#ffffff"
|
||||
@ -1433,35 +1535,76 @@
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:label="battery-amp-text"
|
||||
id="layer64"
|
||||
inkscape:groupmode="layer"
|
||||
transform="translate(0,0.768478)"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="battery-amp-text"
|
||||
style="font-size:10px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
transform="translate(0,17)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4599"
|
||||
style="fill:#ffffff"
|
||||
d="m 575.65771,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.2539,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12696,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89356,-0.249023 1.14747,-0.747071 0.25715,-0.5013 0.38573,-1.251625 0.38574,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.6364,-0.7519463 -1.14747,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64942,2.8125003 -10e-6,1.227216 -0.21648,2.164715 -0.64942,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81705,-10e-7 -1.44205,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43295,-0.6477793 1.05795,-0.9716722 1.875,-0.9716797" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4602"
|
||||
style="fill:#ffffff"
|
||||
d="m 582.0249,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -1e-5,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4604"
|
||||
style="fill:#ffffff"
|
||||
d="m 586.28271,14.849686 1.03028,0 0,1.240234 -1.03028,0 0,-1.240234" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4606"
|
||||
style="fill:#ffffff"
|
||||
d="m 591.57568,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4608"
|
||||
style="fill:#ffffff"
|
||||
d="m 597.94287,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38574,-2.250976 0,-1.0026 -0.12858,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81705,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05307,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer65"
|
||||
inkscape:label="battery-volt-text">
|
||||
inkscape:label="battery-volt-text"
|
||||
transform="translate(0,-1.231522)"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:10px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="battery-volt-text">
|
||||
id="battery-volt-text"
|
||||
transform="translate(0,2)">
|
||||
<path
|
||||
d="m 575.65771,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.2539,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12696,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89356,-0.249023 1.14747,-0.747071 0.25715,-0.5013 0.38573,-1.251625 0.38574,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.6364,-0.7519463 -1.14747,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64942,2.8125003 -10e-6,1.227216 -0.21648,2.164715 -0.64942,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81705,-10e-7 -1.44205,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43295,-0.6477793 1.05795,-0.9716722 1.875,-0.9716797"
|
||||
d="m 575.65771,8.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.2539,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12696,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89356,-0.249023 1.14747,-0.747071 0.25715,-0.5013 0.38573,-1.251625 0.38574,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.6364,-0.7519463 -1.14747,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64942,2.8125003 -10e-6,1.227216 -0.21648,2.164715 -0.64942,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81705,-10e-7 -1.44205,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43295,-0.6477793 1.05795,-0.9716722 1.875,-0.9716797"
|
||||
style="fill:#ffffff"
|
||||
id="path6483"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 582.0249,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -1e-5,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
d="m 582.0249,8.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -1e-5,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
style="fill:#ffffff"
|
||||
id="path6485"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 586.28271,14.849686 1.03028,0 0,1.240234 -1.03028,0 0,-1.240234"
|
||||
d="m 586.28271,13.849686 1.03028,0 0,1.240234 -1.03028,0 0,-1.240234"
|
||||
style="fill:#ffffff"
|
||||
id="path6487"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 591.57568,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
d="m 591.57568,8.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38575,-2.250976 -10e-6,-1.0026 -0.12859,-1.752925 -0.38575,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81706,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05306,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42968,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21485,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
style="fill:#ffffff"
|
||||
id="path6489"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 597.94287,9.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38574,-2.250976 0,-1.0026 -0.12858,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81705,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05307,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
d="m 597.94287,8.449295 c -0.50781,6.7e-6 -0.8903,0.2506575 -1.14746,0.751953 -0.25391,0.498052 -0.38086,1.248377 -0.38086,2.250977 0,0.999351 0.12695,1.749676 0.38086,2.250976 0.25716,0.498048 0.63965,0.747071 1.14746,0.747071 0.51107,0 0.89355,-0.249023 1.14746,-0.747071 0.25716,-0.5013 0.38574,-1.251625 0.38574,-2.250976 0,-1.0026 -0.12858,-1.752925 -0.38574,-2.250977 -0.25391,-0.5012955 -0.63639,-0.7519463 -1.14746,-0.751953 m 0,-0.78125 c 0.81705,7.5e-6 1.44043,0.3239004 1.87012,0.9716797 0.43294,0.6445373 0.64941,1.5820363 0.64941,2.8125003 0,1.227216 -0.21647,2.164715 -0.64941,2.8125 -0.42969,0.644531 -1.05307,0.966796 -1.87012,0.966797 -0.81706,-10e-7 -1.44206,-0.322266 -1.875,-0.966797 -0.42969,-0.647785 -0.64453,-1.585284 -0.64453,-2.8125 0,-1.230464 0.21484,-2.167963 0.64453,-2.8125003 0.43294,-0.6477793 1.05794,-0.9716722 1.875,-0.9716797"
|
||||
style="fill:#ffffff"
|
||||
id="path6491"
|
||||
inkscape:connector-curvature="0" />
|
||||
@ -1472,79 +1615,101 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer63"
|
||||
inkscape:label="throttle"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
style="fill:#008080;stroke:#000000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 469.86993,48.85 0,-2.5"
|
||||
id="eng0"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="eng1"
|
||||
d="m 469,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="m 469.86993,48.85 0,-2.5"
|
||||
style="fill:#008080;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10211"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 477,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 477.38975,48.85 0,-5.000001"
|
||||
id="eng2"
|
||||
inkscape:connector-curvature="0" />
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10213"
|
||||
inkscape:connector-curvature="0"
|
||||
id="eng3"
|
||||
d="m 485,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="m 484.90956,48.85 0,-7.500001"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10215"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 493,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 492.42936,48.85 0,-10"
|
||||
id="eng4"
|
||||
inkscape:connector-curvature="0" />
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10217"
|
||||
inkscape:connector-curvature="0"
|
||||
id="eng5"
|
||||
d="m 501,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="m 499.94918,48.85 0,-12.500001"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10219"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 509,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 507.46898,48.85 0,-15.000001"
|
||||
id="eng6"
|
||||
inkscape:connector-curvature="0" />
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10221"
|
||||
inkscape:connector-curvature="0"
|
||||
id="eng7"
|
||||
d="m 517,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="m 514.98879,48.85 0,-17.500001"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10223"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 525,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 522.5086,48.85 0,-20.000002"
|
||||
id="eng8"
|
||||
inkscape:connector-curvature="0" />
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10225"
|
||||
inkscape:connector-curvature="0"
|
||||
id="eng9"
|
||||
d="m 533,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="m 530.02841,48.85 0,-22.500001"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:label="#path10227"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 541,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:8.30000019;stroke-linecap:square;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 537.54822,48.85 0,-25.000001"
|
||||
id="eng10"
|
||||
inkscape:connector-curvature="0" />
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer58"
|
||||
inkscape:label="waypoint">
|
||||
inkscape:label="waypoint"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer20"
|
||||
inkscape:label="waypoint-eta-text">
|
||||
inkscape:label="waypoint-eta-text"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ff00ff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="waypoint-eta-text">
|
||||
id="waypoint-eta-text"
|
||||
transform="translate(0,3.595328)">
|
||||
<path
|
||||
d="m 400.29349,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 0,1.199222 0.15234,2.099611 0.45703,2.701172 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016"
|
||||
style="font-size:12px;fill:#ff00ff"
|
||||
@ -1590,10 +1755,12 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer61"
|
||||
inkscape:label="waypoint-distance-text">
|
||||
inkscape:label="waypoint-distance-text"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ff00ff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="waypoint-distance-text">
|
||||
id="waypoint-distance-text"
|
||||
transform="translate(0,3.595328)">
|
||||
<path
|
||||
d="m 303.29349,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 0,1.199222 0.15234,2.099611 0.45703,2.701172 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016"
|
||||
style="font-size:12px;fill:#ff00ff"
|
||||
@ -1639,10 +1806,12 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer60"
|
||||
inkscape:label="waypoint-heading-text">
|
||||
inkscape:label="waypoint-heading-text"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ff00ff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="waypoint-heading-text">
|
||||
id="waypoint-heading-text"
|
||||
transform="translate(0,3.595328)">
|
||||
<path
|
||||
d="m 216.29349,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 0,1.199222 0.15234,2.099611 0.45703,2.701172 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016"
|
||||
style="font-size:12px;fill:#ff00ff"
|
||||
@ -1663,10 +1832,12 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer18"
|
||||
inkscape:label="waypoint-mode-text">
|
||||
inkscape:label="waypoint-mode-text"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ff00ff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="waypoint-mode-text">
|
||||
id="waypoint-mode-text"
|
||||
transform="translate(0,3.595328)">
|
||||
<path
|
||||
d="m 346.84036,8.3145294 0,6.8027346 1.42969,0 c 1.20703,10e-7 2.08984,-0.273436 2.64844,-0.820313 0.56249,-0.546872 0.84374,-1.410153 0.84375,-2.589843 -1e-5,-1.17187 -0.28126,-2.0292909 -0.84375,-2.5722661 -0.5586,-0.5468675 -1.44141,-0.8203047 -2.64844,-0.8203125 l -1.42969,0 m -1.18359,-0.9726562 2.43164,0 c 1.69531,8.7e-6 2.93945,0.353524 3.73242,1.0605468 0.79296,0.703132 1.18945,1.804693 1.18945,3.304688 0,1.507815 -0.39844,2.615236 -1.19531,3.322265 -0.79688,0.707032 -2.03907,1.060547 -3.72656,1.060547 l -2.43164,0 0,-8.7480468"
|
||||
style="font-size:12px;fill:#ff00ff"
|
||||
@ -1753,10 +1924,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer56"
|
||||
inkscape:label="waypoint-description-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ff00ff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="waypoint-description-text">
|
||||
id="waypoint-description-text"
|
||||
transform="translate(0,3.595328)">
|
||||
<path
|
||||
d="m 217.92825,10.523514 0,-3.5507815 1.07813,0 0,9.1171875 -1.07813,0 0,-0.984375 c -0.22656,0.390626 -0.51367,0.681641 -0.86132,0.873047 -0.34376,0.1875 -0.75782,0.28125 -1.24219,0.28125 -0.79297,0 -1.43946,-0.316406 -1.93946,-0.949219 -0.49609,-0.632811 -0.74414,-1.464841 -0.74414,-2.496094 0,-1.031245 0.24805,-1.863276 0.74414,-2.496093 0.5,-0.6328064 1.14649,-0.9492124 1.93946,-0.9492191 0.48437,6.7e-6 0.89843,0.09571 1.24219,0.2871094 0.34765,0.1875062 0.63476,0.4765687 0.86132,0.8671877 m -3.67382,2.291015 c -1e-5,0.792972 0.1621,1.416018 0.48632,1.869141 0.32813,0.44922 0.77734,0.673829 1.34766,0.673828 0.57031,1e-6 1.01953,-0.224608 1.34766,-0.673828 0.32812,-0.453123 0.49218,-1.076169 0.49218,-1.869141 0,-0.792964 -0.16406,-1.414057 -0.49218,-1.863281 -0.32813,-0.453119 -0.77735,-0.679682 -1.34766,-0.679687 -0.57032,5e-6 -1.01953,0.226568 -1.34766,0.679687 -0.32422,0.449224 -0.48633,1.070317 -0.48632,1.863281"
|
||||
style="font-size:12px;fill:#ff00ff"
|
||||
@ -1834,219 +2007,480 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer59"
|
||||
inkscape:label="telemetry"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer45"
|
||||
inkscape:label="telemetry-status"
|
||||
style="display:inline"
|
||||
transform="translate(0,0.863767)"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="translate(-8,6.595328)"
|
||||
style="font-size:10px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Arial"
|
||||
id="telemetry-status">
|
||||
<path
|
||||
d="m 128.40151,44.014168 0,-6.313477 -2.3584,0 0,-0.844726 5.67383,0 0,0.844726 -2.36816,0 0,6.313477 -0.94727,0"
|
||||
id="path4935"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 131.76577,44.014168 0,-1.000977 1.00098,0 0,1.000977 -1.00098,0"
|
||||
id="path4937"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 134.08999,41.714363 0.89355,-0.07813 c 0.0423,0.358075 0.13998,0.652671 0.29297,0.883789 0.15625,0.227866 0.39714,0.413413 0.72266,0.556641 0.32552,0.139975 0.69173,0.209961 1.09863,0.209961 0.36133,0 0.68034,-0.05371 0.95703,-0.161133 0.27669,-0.107421 0.48177,-0.253905 0.61524,-0.439453 0.13671,-0.188801 0.20507,-0.393879 0.20507,-0.615235 0,-0.224607 -0.0651,-0.419919 -0.19531,-0.585937 -0.13021,-0.169268 -0.34505,-0.31087 -0.64453,-0.424805 -0.19206,-0.07487 -0.61686,-0.190426 -1.27441,-0.346679 -0.65756,-0.159502 -1.11817,-0.309242 -1.38184,-0.449219 -0.3418,-0.179033 -0.59733,-0.400387 -0.7666,-0.664063 -0.16602,-0.266922 -0.24902,-0.564773 -0.24902,-0.893554 0,-0.361323 0.10253,-0.698237 0.30761,-1.010743 0.20508,-0.315748 0.50456,-0.555006 0.89844,-0.717773 0.39388,-0.162753 0.8317,-0.244133 1.31348,-0.244141 0.53059,8e-6 0.99771,0.08627 1.40136,0.258789 0.4069,0.169278 0.7194,0.419929 0.9375,0.751954 0.2181,0.332037 0.33529,0.708013 0.35157,1.127929 l -0.90821,0.06836 c -0.0488,-0.452469 -0.21484,-0.794265 -0.49804,-1.025391 -0.27996,-0.231113 -0.69499,-0.346673 -1.24512,-0.34668 -0.57292,7e-6 -0.99121,0.105801 -1.25488,0.317383 -0.26042,0.208339 -0.39063,0.460618 -0.39063,0.756836 0,0.257167 0.0928,0.468755 0.27832,0.634766 0.18229,0.16602 0.65755,0.336918 1.42578,0.512695 0.77148,0.17253 1.30045,0.323897 1.58692,0.454102 0.41666,0.19206 0.72428,0.436201 0.92285,0.732421 0.19856,0.292972 0.29784,0.631513 0.29785,1.015625 -1e-5,0.380861 -0.10905,0.740562 -0.32715,1.079102 -0.2181,0.335287 -0.53223,0.597331 -0.94238,0.786133 -0.40691,0.185547 -0.86589,0.27832 -1.37695,0.27832 -0.64779,0 -1.19141,-0.0944 -1.63086,-0.283203 -0.4362,-0.188802 -0.77963,-0.472005 -1.03028,-0.849609 -0.24739,-0.380858 -0.3776,-0.810545 -0.39062,-1.289063"
|
||||
id="path4939"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 142.89858,43.228035 0.12696,0.776367 c -0.2474,0.05208 -0.46876,0.07813 -0.66407,0.07813 -0.31901,0 -0.5664,-0.05046 -0.74218,-0.151367 -0.17579,-0.100911 -0.29948,-0.232747 -0.3711,-0.395508 -0.0716,-0.166015 -0.10742,-0.512694 -0.10742,-1.040039 l 0,-2.983398 -0.64453,0 0,-0.683594 0.64453,0 0,-1.28418 0.87402,-0.527344 0,1.811524 0.88379,0 0,0.683594 -0.88379,0 0,3.032226 c 0,0.250652 0.0146,0.411785 0.0439,0.483399 0.0325,0.07162 0.083,0.128581 0.15137,0.170898 0.0716,0.04232 0.17252,0.06348 0.30273,0.06348 0.0976,0 0.22623,-0.01139 0.38574,-0.03418"
|
||||
id="path4942"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 147.13686,43.374519 c -0.32552,0.276693 -0.63965,0.472006 -0.94238,0.585938 -0.29948,0.113932 -0.62175,0.170898 -0.9668,0.170898 -0.56966,0 -1.00748,-0.138346 -1.31347,-0.415039 -0.30599,-0.279947 -0.45899,-0.636392 -0.45899,-1.069336 0,-0.253904 0.057,-0.485024 0.1709,-0.693359 0.11719,-0.211586 0.26856,-0.380857 0.4541,-0.507813 0.1888,-0.12695 0.40039,-0.222979 0.63477,-0.288086 0.17252,-0.04557 0.43294,-0.08951 0.78125,-0.131835 0.70963,-0.08463 1.23209,-0.185544 1.56738,-0.302735 0.003,-0.120439 0.005,-0.196936 0.005,-0.229492 0,-0.358069 -0.083,-0.610347 -0.24902,-0.756836 -0.22461,-0.198563 -0.55827,-0.297847 -1.00098,-0.297852 -0.41341,5e-6 -0.7194,0.07325 -0.91796,0.219727 -0.19532,0.143233 -0.34018,0.398767 -0.43457,0.766602 l -0.85938,-0.117188 c 0.0781,-0.367834 0.20671,-0.664058 0.38574,-0.888672 0.17904,-0.22786 0.43783,-0.402013 0.77637,-0.522461 0.33854,-0.123692 0.73079,-0.185541 1.17676,-0.185547 0.4427,6e-6 0.8024,0.05209 1.0791,0.15625 0.27669,0.104172 0.48014,0.236008 0.61035,0.395508 0.1302,0.156255 0.22135,0.354822 0.27344,0.595703 0.0293,0.149744 0.0439,0.419926 0.0439,0.810547 l 0,1.171875 c 0,0.817059 0.0179,1.334636 0.0537,1.552735 0.0391,0.214844 0.11393,0.421549 0.22461,0.620117 l -0.91797,0 c -0.0911,-0.182292 -0.14974,-0.395508 -0.17578,-0.639649 m -0.0732,-1.96289 c -0.31901,0.130211 -0.79753,0.240888 -1.43555,0.332031 -0.36133,0.05209 -0.61686,0.110679 -0.7666,0.175781 -0.14974,0.06511 -0.2653,0.161135 -0.34668,0.288086 -0.0814,0.1237 -0.12207,0.262046 -0.12207,0.415039 0,0.234376 0.0879,0.429689 0.26367,0.585938 0.17904,0.15625 0.43946,0.234375 0.78125,0.234375 0.33854,0 0.63965,-0.07324 0.90333,-0.219727 0.26366,-0.149738 0.45735,-0.353189 0.58105,-0.610351 0.0944,-0.198567 0.1416,-0.491535 0.1416,-0.878907 l 0,-0.322265"
|
||||
id="path4944"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 151.23843,43.228035 0.12695,0.776367 c -0.2474,0.05208 -0.46875,0.07813 -0.66406,0.07813 -0.31902,0 -0.56641,-0.05046 -0.74219,-0.151367 -0.17578,-0.100911 -0.29948,-0.232747 -0.37109,-0.395508 -0.0716,-0.166015 -0.10743,-0.512694 -0.10743,-1.040039 l 0,-2.983398 -0.64453,0 0,-0.683594 0.64453,0 0,-1.28418 0.87403,-0.527344 0,1.811524 0.88379,0 0,0.683594 -0.88379,0 0,3.032226 c 0,0.250652 0.0146,0.411785 0.0439,0.483399 0.0325,0.07162 0.083,0.128581 0.15137,0.170898 0.0716,0.04232 0.17252,0.06348 0.30273,0.06348 0.0977,0 0.22624,-0.01139 0.38575,-0.03418"
|
||||
id="path4946"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 155.49136,44.014168 0,-0.761719 c -0.40365,0.585938 -0.95216,0.878906 -1.64551,0.878906 -0.30599,0 -0.59245,-0.05859 -0.85938,-0.175781 -0.26367,-0.117187 -0.46061,-0.263672 -0.59082,-0.439453 -0.12695,-0.179036 -0.21647,-0.397135 -0.26855,-0.654297 -0.0358,-0.172525 -0.0537,-0.445962 -0.0537,-0.820312 l 0,-3.212891 0.8789,0 0,2.875976 c 0,0.458987 0.0179,0.768231 0.0537,0.927735 0.0553,0.231121 0.17253,0.413412 0.35157,0.546875 0.17903,0.130209 0.40039,0.195313 0.66406,0.195312 0.26367,10e-7 0.51106,-0.06673 0.74219,-0.200195 0.23111,-0.136718 0.39387,-0.320637 0.48828,-0.551758 0.0976,-0.234373 0.14648,-0.572914 0.14648,-1.015625 l 0,-2.77832 0.87891,0 0,5.185547 -0.78613,0"
|
||||
id="path4948"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
d="m 157.30776,42.466316 0.86914,-0.136719 c 0.0488,0.348309 0.18392,0.615236 0.40528,0.800782 0.2246,0.185547 0.5371,0.278321 0.9375,0.27832 0.40364,1e-6 0.70312,-0.08138 0.89843,-0.244141 0.19531,-0.166014 0.29297,-0.359699 0.29297,-0.581054 0,-0.198566 -0.0863,-0.354816 -0.25879,-0.46875 -0.12044,-0.07812 -0.41992,-0.177407 -0.89843,-0.297852 -0.64454,-0.162758 -1.09213,-0.302732 -1.34278,-0.419922 -0.24739,-0.12044 -0.4362,-0.284828 -0.5664,-0.493164 -0.12696,-0.211585 -0.19043,-0.444332 -0.19043,-0.698242 0,-0.231116 0.0521,-0.444332 0.15625,-0.639648 0.10742,-0.198563 0.25227,-0.362951 0.43457,-0.493164 0.13671,-0.100907 0.32226,-0.185542 0.55664,-0.253907 0.23763,-0.07161 0.49153,-0.107416 0.76172,-0.107422 0.40689,6e-6 0.76334,0.0586 1.06933,0.175782 0.30924,0.117192 0.53711,0.276697 0.6836,0.478515 0.14648,0.198572 0.24739,0.465499 0.30273,0.800782 l -0.85937,0.117187 c -0.0391,-0.266923 -0.153,-0.475256 -0.3418,-0.625 -0.18555,-0.149735 -0.44922,-0.224605 -0.79102,-0.224609 -0.40365,4e-6 -0.69173,0.06674 -0.86426,0.200195 -0.17252,0.133468 -0.25879,0.289718 -0.25878,0.46875 -10e-6,0.113936 0.0358,0.216475 0.10742,0.307617 0.0716,0.09441 0.18392,0.17253 0.33691,0.234375 0.0879,0.03256 0.34668,0.107425 0.77637,0.22461 0.62174,0.166018 1.05468,0.302737 1.29883,0.410156 0.24739,0.104169 0.44107,0.257164 0.58105,0.458984 0.13997,0.201825 0.20996,0.452476 0.20996,0.751953 0,0.29297 -0.0863,0.569663 -0.25879,0.830078 -0.16927,0.257162 -0.41504,0.457357 -0.7373,0.600586 -0.32227,0.139974 -0.68685,0.209961 -1.09375,0.209961 -0.67383,0 -1.18815,-0.139974 -1.54297,-0.419922 -0.35156,-0.279947 -0.57617,-0.694986 -0.67383,-1.245117"
|
||||
id="path4950"
|
||||
inkscape:connector-curvature="0" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer54"
|
||||
inkscape:label="telemetry-rx"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 120,34.5 0,-11.082914"
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx0"
|
||||
d="m 110,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#000000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 114,36.5 0,-11.082914"
|
||||
id="rx1"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx2"
|
||||
d="m 126,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 116.5,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10211" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 132,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 119,36.5 0,-11.082914"
|
||||
id="rx3"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10213" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx4"
|
||||
d="m 138,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 121.5,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10215" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 144,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 124,36.5 0,-11.082914"
|
||||
id="rx5"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10217" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx6"
|
||||
d="m 150,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 126.5,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10219" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 156,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 129,36.5 0,-11.082914"
|
||||
id="rx7"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10221" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx8"
|
||||
d="m 162,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 131.5,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10223" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 168,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 134,36.5 0,-11.082914"
|
||||
id="rx9"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10225" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx10"
|
||||
d="m 174,34.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 136.5,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10227" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx11"
|
||||
d="m 139,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 141.5,36.5 0,-11.082914"
|
||||
id="rx12"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx13"
|
||||
d="m 144,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 146.5,36.5 0,-11.082914"
|
||||
id="rx14"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx15"
|
||||
d="m 149,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 151.5,36.5 0,-11.082914"
|
||||
id="rx16"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx17"
|
||||
d="m 154,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 156.5,36.5 0,-11.082914"
|
||||
id="rx18"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx19"
|
||||
d="m 159,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 161.5,36.5 0,-11.082914"
|
||||
id="rx20"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx21"
|
||||
d="m 164,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 166.5,36.5 0,-11.082914"
|
||||
id="rx22"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx23"
|
||||
d="m 169,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 171.5,36.5 0,-11.082914"
|
||||
id="rx24"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="rx25"
|
||||
d="m 174,36.5 0,-11.082914"
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer55"
|
||||
inkscape:label="telemetry-tx"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 110,18.095328 110,7.012414"
|
||||
id="tx0"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx1"
|
||||
d="M 120,17.5 120,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="M 114,18.095328 114,7.012414"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:label="#path10211"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 126,17.5 126,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 116.5,18.095328 0,-11.082914"
|
||||
id="tx2"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:label="#path10213"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx3"
|
||||
d="M 132,17.5 132,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="M 119,18.095328 119,7.012414"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:label="#path10215"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 138,17.5 138,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 121.5,18.095328 0,-11.082914"
|
||||
id="tx4"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:label="#path10217"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx5"
|
||||
d="M 144,17.5 144,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="M 124,18.095328 124,7.012414"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:label="#path10219"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 150,17.5 150,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 126.5,18.095328 0,-11.082914"
|
||||
id="tx6"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:label="#path10221"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx7"
|
||||
d="M 156,17.5 156,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="M 129,18.095328 129,7.012414"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:label="#path10223"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 162,17.5 162,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 131.5,18.095328 0,-11.082914"
|
||||
id="tx8"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
inkscape:label="#path10225"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx9"
|
||||
d="M 168,17.5 168,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
d="M 134,18.095328 134,7.012414"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
inkscape:label="#path10227"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 174,17.5 174,6.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 136.5,18.095328 0,-11.082914"
|
||||
id="tx10"
|
||||
inkscape:connector-curvature="0" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 139,18.095328 139,7.012414"
|
||||
id="tx11"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx12"
|
||||
d="m 141.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 144,18.095328 144,7.012414"
|
||||
id="tx13"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx14"
|
||||
d="m 146.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#008000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 149,18.095328 149,7.012414"
|
||||
id="tx15"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx16"
|
||||
d="m 151.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 154,18.095328 154,7.012414"
|
||||
id="tx17"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx18"
|
||||
d="m 156.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 159,18.095328 159,7.012414"
|
||||
id="tx19"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx20"
|
||||
d="m 161.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff8000;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 164,18.095328 164,7.012414"
|
||||
id="tx21"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx22"
|
||||
d="m 166.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 169,18.095328 169,7.012414"
|
||||
id="tx23"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
<path
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="tx24"
|
||||
d="m 171.5,18.095328 0,-11.082914"
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff1400;stroke-width:3;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="M 174,18.095328 174,7.012414"
|
||||
id="tx25"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer57"
|
||||
inkscape:label="gps"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer53"
|
||||
inkscape:label="gps-sats"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 30,34.5 30,23.417086"
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:label="#path10180"
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps0"
|
||||
d="m 28,51.5 0,-5"
|
||||
style="fill:none;stroke:#000000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 28,51.5 0,-5"
|
||||
id="gps1"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10180" />
|
||||
inkscape:label="#path10180"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps2"
|
||||
d="M 36,34.5 36,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
inkscape:label="#path10211" />
|
||||
d="m 34,51.5 0,-7"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10211"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 42,34.5 42,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 40,51.5 0,-9"
|
||||
id="gps3"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10213" />
|
||||
inkscape:label="#path10213"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps4"
|
||||
d="M 48,34.5 48,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
inkscape:label="#path10215" />
|
||||
d="m 46,51.5 0,-11"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10215"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 54,34.5 54,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 52,51.5 0,-13"
|
||||
id="gps5"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10217" />
|
||||
inkscape:label="#path10217"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps6"
|
||||
d="M 60,34.5 60,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
inkscape:label="#path10219" />
|
||||
d="m 58,51.5 0,-15"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10219"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 66,34.5 66,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 64,51.5 0,-17"
|
||||
id="gps7"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10221" />
|
||||
inkscape:label="#path10221"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps8"
|
||||
d="M 72,34.5 72,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
inkscape:label="#path10223" />
|
||||
d="m 70,51.5 0,-19"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10223"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="M 78,34.5 78,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
d="m 76,51.5 0,-21"
|
||||
id="gps9"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10225" />
|
||||
inkscape:label="#path10225"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="gps10"
|
||||
d="M 84,34.5 84,23.417086"
|
||||
style="fill:none;stroke:#008000;stroke-width:4;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
inkscape:label="#path10227" />
|
||||
d="m 82,51.5 0,-23"
|
||||
style="fill:none;stroke:#008000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline"
|
||||
inkscape:label="#path10227"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer52"
|
||||
inkscape:label="gps-mode-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
transform="translate(0,-0.972157)">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="gps-mode-text">
|
||||
id="gps-mode-text"
|
||||
transform="translate(0,1)">
|
||||
<path
|
||||
d="m 54.155106,11.899892 c 0.472,0.100915 0.839838,0.310876 1.103515,0.629883 0.266922,0.319013 0.400385,0.712893 0.400391,1.18164 -6e-6,0.719403 -0.247401,1.276043 -0.742188,1.669922 -0.494796,0.39388 -1.19792,0.59082 -2.109375,0.59082 -0.305992,0 -0.621747,-0.03092 -0.947265,-0.09277 -0.322267,-0.05859 -0.655926,-0.148112 -1.000977,-0.268555 l 0,-0.952148 c 0.273437,0.159506 0.572915,0.279949 0.898438,0.361328 0.325519,0.08138 0.665687,0.122071 1.020507,0.12207 0.618487,10e-7 1.088864,-0.122069 1.411133,-0.366211 0.325517,-0.244139 0.488277,-0.598956 0.488282,-1.064453 -5e-6,-0.429685 -0.151372,-0.764971 -0.454102,-1.005859 -0.299483,-0.244137 -0.717777,-0.366208 -1.254883,-0.366211 l -0.849609,0 0,-0.810547 0.888672,0 c 0.485022,4e-6 0.856116,-0.09602 1.113281,-0.288086 0.257157,-0.195308 0.385738,-0.475255 0.385742,-0.839844 C 54.506664,10.026525 54.3732,9.7400672 54.106277,9.5414934 53.842602,9.339677 53.46337,9.2387656 52.968582,9.238759 c -0.270185,6.6e-6 -0.559898,0.029303 -0.86914,0.087891 -0.309247,0.0586 -0.649416,0.1497459 -1.020508,0.2734375 l 0,-0.8789063 c 0.374347,-0.1041594 0.724282,-0.1822844 1.049804,-0.234375 0.328774,-0.052076 0.638019,-0.078118 0.927735,-0.078125 0.748694,7.4e-6 1.341141,0.1709057 1.777344,0.5126953 0.436192,0.3385483 0.654291,0.7975322 0.654296,1.3769525 -5e-6,0.403651 -0.115565,0.745448 -0.346679,1.025391 -0.231125,0.276697 -0.559901,0.468754 -0.986328,0.576172"
|
||||
style="font-size:10px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
@ -2060,19 +2494,61 @@
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer23"
|
||||
inkscape:label="info-fg"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:none;stroke:#000000;stroke-width:2.5;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="m 25,51.418075 60,0.08193 0,-22.998652 -6,-0.0014 0,22.992116 -6,-0.0088 0,-20.97668 6,0.04472 -6,-0.04472 0,2.12303 -6,3.48e-4 0,18.845475 -6,-0.0069 0.02494,-16.83188 5.97506,-0.007 -6.024941,0.007 0.02494,1.934623 -6,-0.07128 0,14.959092 -6,-0.0081 0,-12.950991 6,-3.28e-4 -6,3.28e-4 0,2 -6,0 0,10.942406 0,-8.942406 -6,0 0,8.93472 0,-6.93472 -6,0 0,6.926248 0,-4.926248 -6,5e-6 z"
|
||||
id="satbar-mask"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="ccccccccccccccccccccccccccccccccccc"
|
||||
inkscape:label="satbar-mask" />
|
||||
<path
|
||||
inkscape:label="throttle-mask"
|
||||
inkscape:connector-curvature="0"
|
||||
id="throttle-mask"
|
||||
d="m 466.25103,52.7 c 75.34867,0 75.1981,0 75.1981,0 l 0,-35 -75.1981,25 0,10"
|
||||
style="fill:none;stroke:#000000;stroke-width:4.5999999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
sodipodi:nodetypes="ccccc" />
|
||||
<rect
|
||||
style="fill:none;stroke:#0c0f0c;stroke-width:3;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="tx-mask"
|
||||
width="64"
|
||||
height="12.5"
|
||||
x="112"
|
||||
y="2.5"
|
||||
transform="translate(0,4)"
|
||||
inkscape:label="tx-mask"
|
||||
ry="2.3730814" />
|
||||
<rect
|
||||
ry="2.3730814"
|
||||
inkscape:label="rx-mask"
|
||||
y="24.5"
|
||||
x="112"
|
||||
height="12.5"
|
||||
width="64"
|
||||
id="rx-mask"
|
||||
style="fill:none;stroke:#0c0f0c;stroke-width:3;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
rx="2.3730814" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer22"
|
||||
inkscape:label="roll-scale"
|
||||
sodipodi:insensitive="true"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
transform="translate(0,38)"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="translate(0,-4)"
|
||||
style="display:inline"
|
||||
id="roll-scale"
|
||||
inkscape:label="#g3634"
|
||||
inkscape:transform-center-y="-108.72348">
|
||||
inkscape:transform-center-y="-146.72348"
|
||||
transform="translate(0,8)">
|
||||
<path
|
||||
transform="translate(0,4)"
|
||||
inkscape:transform-center-x="31.416405"
|
||||
@ -2210,7 +2686,7 @@
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
style="fill:#ffffff;stroke:none;display:inline"
|
||||
d="m 311.95,44.002 8.08652,15 8.01834,-15 z"
|
||||
d="m 311.913,44.002 8.08652,15 8.01834,-15 z"
|
||||
id="path8288"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:transform-center-y="-7.5"
|
||||
@ -2226,30 +2702,33 @@
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
inkscape:label="sideslip-fixed">
|
||||
id="g3851"
|
||||
inkscape:label="sideslip-moving"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:#ffffff;stroke:none;display:inline"
|
||||
d="M 324.45251,68.162312 320,59.903176 l -4.41496,8.259136 z"
|
||||
d="m 328.90502,126.42145 -2.96834,-5.50609 -11.82329,0 -2.9433,5.50609 z"
|
||||
id="sideslip-moving"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:transform-center-y="11.012182"
|
||||
sodipodi:nodetypes="ccccc"
|
||||
inkscape:label="#path8293" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
inkscape:label="sideslip-fixed"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:#ffffff;stroke:none;display:inline"
|
||||
d="M 324.45251,118.16231 320,109.90318 l -4.41496,8.25913 z"
|
||||
id="sideslip-fixed"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:transform-center-y="11.012182"
|
||||
sodipodi:nodetypes="cccc"
|
||||
inkscape:label="#path3601" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer23"
|
||||
inkscape:label="sideslip_moving">
|
||||
<path
|
||||
style="fill:#ffffff;stroke:none;display:inline"
|
||||
d="m 328.90502,76.421448 -2.96834,-5.50609 -11.82329,0 -2.9433,5.50609 z"
|
||||
id="slideslip-moving"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:transform-center-y="11.012182"
|
||||
sodipodi:nodetypes="ccccc"
|
||||
inkscape:label="#path8293" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
@ -2261,7 +2740,7 @@
|
||||
<g
|
||||
id="center-plane"
|
||||
inkscape:label="#g10116"
|
||||
transform="matrix(0.75001087,0,0,0.75001087,79.995225,52.248163)"
|
||||
transform="matrix(0.75001087,0,0,0.75001087,79.995225,94.24816)"
|
||||
inkscape:transform-center-y="8.437616">
|
||||
<path
|
||||
id="path4955"
|
||||
@ -2279,12 +2758,14 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer49"
|
||||
inkscape:label="center-arrows">
|
||||
inkscape:label="center-arrows"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="center-arrows"
|
||||
inkscape:label="#g10100"
|
||||
transform="matrix(0.82206736,0,0,0.82206736,56.949678,40.071298)">
|
||||
transform="matrix(0.82206736,0,0,0.82206736,56.949683,82.071297)">
|
||||
<g
|
||||
transform="translate(29.51,-10.5)"
|
||||
inkscape:transform-center-x="101.52064"
|
||||
@ -2331,7 +2812,9 @@
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer50"
|
||||
inkscape:label="center-plane" />
|
||||
inkscape:label="center-plane"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
@ -2344,27 +2827,30 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer70"
|
||||
inkscape:label="compass-vector"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="compass-vector"
|
||||
width="50"
|
||||
height="5.5"
|
||||
x="320"
|
||||
y="289.10001"
|
||||
y="367.10001"
|
||||
inkscape:label="#rect4838" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer10"
|
||||
inkscape:label="compass-fixed"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="compass-fixed"
|
||||
inkscape:label="#g9078">
|
||||
inkscape:label="#g9078"
|
||||
transform="translate(0,78)">
|
||||
<path
|
||||
transform="matrix(0.84971585,0,0,0.84971585,73.153736,57.627199)"
|
||||
d="m 381.49999,370 a 91.010612,91.010612 0 1 1 -182.02122,0 91.010612,91.010612 0 1 1 182.02122,0 z"
|
||||
d="m 381.49999,370 c 0,50.26377 -40.74684,91.01061 -91.01061,91.01061 -50.26377,0 -91.01061,-40.74684 -91.01061,-91.01061 0,-50.26377 40.74684,-91.01061 91.01061,-91.01061 50.26377,0 91.01061,40.74684 91.01061,91.01061 z"
|
||||
sodipodi:ry="91.010612"
|
||||
sodipodi:rx="91.010612"
|
||||
sodipodi:cy="370"
|
||||
@ -2374,7 +2860,7 @@
|
||||
sodipodi:type="arc" />
|
||||
<path
|
||||
style="fill:#000000;fill-opacity:0.25098039;fill-rule:evenodd;stroke:none;display:inline"
|
||||
d="m 300.325,288.83216 0,8.32484 c 14.21621,-3.46975 26.48893,-3.18251 38.975,-0.032 l 0,-8.32842 z"
|
||||
d="m 300.325,286.83216 0,10.32484 c 14.21621,-3.46975 26.48893,-3.18251 38.975,-0.032 l 0,-10.32842 z"
|
||||
id="path6040"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="ccccc" />
|
||||
@ -2384,7 +2870,8 @@
|
||||
height="17.963617"
|
||||
width="38.967232"
|
||||
id="rect5453"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" />
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline"
|
||||
ry="2.4615386" />
|
||||
<path
|
||||
inkscape:transform-center-x="97.48046"
|
||||
sodipodi:nodetypes="cc"
|
||||
@ -2447,7 +2934,8 @@
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="compass-wheel"
|
||||
inkscape:label="#g9628">
|
||||
inkscape:label="#g9628"
|
||||
transform="translate(0,78)">
|
||||
<path
|
||||
inkscape:transform-center-x="-0.112375"
|
||||
inkscape:transform-center-y="-85.40481"
|
||||
@ -3393,7 +3881,7 @@
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
transform="translate(0.01737791,-0.0606466)"
|
||||
transform="translate(0.01737791,77.939353)"
|
||||
id="compass-vector-arrow"
|
||||
inkscape:label="#g4651">
|
||||
<path
|
||||
@ -3420,7 +3908,7 @@
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="compass-waypoint"
|
||||
transform="translate(0.01737791,-0.06064664)"
|
||||
transform="translate(0.01737791,77.939353)"
|
||||
inkscape:label="#g8899">
|
||||
<path
|
||||
sodipodi:nodetypes="cccccccc"
|
||||
@ -3442,10 +3930,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer11"
|
||||
inkscape:label="compass-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:33.9886322px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="compass-text">
|
||||
id="compass-text"
|
||||
transform="translate(0,78)">
|
||||
<path
|
||||
d="m 311.31955,276.77926 c -0.6904,10e-6 -1.21041,0.34078 -1.56003,1.02232 -0.3452,0.67712 -0.5178,1.69722 -0.51779,3.0603 -1e-5,1.35867 0.17259,2.37877 0.51779,3.06031 0.34962,0.67712 0.86963,1.01567 1.56003,1.01567 0.69481,0 1.21482,-0.33855 1.56002,-1.01567 0.34962,-0.68154 0.52443,-1.70164 0.52444,-3.06031 -1e-5,-1.36308 -0.17482,-2.38318 -0.52444,-3.0603 -0.3452,-0.68154 -0.86521,-1.02231 -1.56002,-1.02232 m 0,-1.06214 c 1.11082,10e-6 1.95832,0.44036 2.54251,1.32104 0.58859,0.87628 0.8829,2.15085 0.8829,3.82372 0,1.66846 -0.29431,2.94303 -0.8829,3.82372 -0.58419,0.87627 -1.43169,1.31441 -2.54251,1.31441 -1.11083,0 -1.96055,-0.43814 -2.54915,-1.31441 -0.58418,-0.88069 -0.87627,-2.15526 -0.87627,-3.82372 0,-1.67287 0.29209,-2.94744 0.87627,-3.82372 0.5886,-0.88068 1.43832,-1.32103 2.54915,-1.32104"
|
||||
style="font-size:13.59545326px;text-align:center;text-anchor:middle;fill:#ffffff"
|
||||
@ -3471,7 +3961,7 @@
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:#00ffff;stroke:none"
|
||||
d="m 320,294.78125 -3.78125,4.5 3.78125,4.5 3.78125,-4.5 -3.78125,-4.5 z"
|
||||
d="m 320,372.78125 -3.78125,4.5 3.78125,4.5 3.78125,-4.5 -3.78125,-4.5 z"
|
||||
id="compass-home"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:transform-center-y="-72.71875"
|
||||
@ -3481,12 +3971,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer30"
|
||||
inkscape:label="compass-plane"
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
style="display:inline">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="compass-plane"
|
||||
d="m 319.99619,361.71926 -2.20395,1.77909 0,4.59378 -8.44405,3.08022 0.0265,2.12429 8.55027,0 -0.0796,4.72654 -2.49604,2.07118 0.0531,2.15085 4.59378,-0.0796 4.56722,0.0796 0.0531,-2.15085 -2.46949,-2.07118 -0.10621,-4.72654 8.55026,0 0.0265,-2.12429 -8.44406,-3.08022 0,-4.59378 -2.17735,-1.77909 z"
|
||||
d="m 319.99619,439.71926 -2.20395,1.77909 0,4.59378 -8.44405,3.08022 0.0265,2.12429 8.55027,0 -0.0796,4.72654 -2.49604,2.07118 0.0531,2.15085 4.59378,-0.0796 4.56722,0.0796 0.0531,-2.15085 -2.46949,-2.07118 -0.10621,-4.72654 8.55026,0 0.0265,-2.12429 -8.44406,-3.08022 0,-4.59378 -2.17735,-1.77909 z"
|
||||
style="fill:#ffffff;stroke:none;display:inline"
|
||||
inkscape:label="#path5448" />
|
||||
</g>
|
||||
@ -3502,10 +3991,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer73"
|
||||
inkscape:label="speed-unit"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans"
|
||||
id="speed-unit">
|
||||
id="speed-unit"
|
||||
transform="translate(0,42)">
|
||||
<path
|
||||
d="m 134.60681,290.91187 c 0.22461,-0.40365 0.49316,-0.7015 0.80567,-0.89356 0.31249,-0.19205 0.68033,-0.28808 1.10351,-0.28809 0.56965,1e-5 1.00911,0.20021 1.31836,0.60059 0.30924,0.39714 0.46386,0.96355 0.46387,1.69922 l 0,3.30078 -0.90332,0 0,-3.27148 c -1e-5,-0.52409 -0.0928,-0.91309 -0.27832,-1.167 -0.18556,-0.2539 -0.46876,-0.38085 -0.84961,-0.38086 -0.4655,1e-5 -0.83334,0.15463 -1.10352,0.46387 -0.27019,0.30925 -0.40528,0.7308 -0.40527,1.26465 l 0,3.09082 -0.90332,0 0,-3.27148 c -1e-5,-0.52734 -0.0928,-0.91634 -0.27832,-1.167 -0.18555,-0.2539 -0.47201,-0.38085 -0.85938,-0.38086 -0.45898,1e-5 -0.82357,0.15626 -1.09375,0.46875 -0.27018,0.30925 -0.40527,0.72917 -0.40527,1.25977 l 0,3.09082 -0.90332,0 0,-5.46875 0.90332,0 0,0.84961 c 0.20508,-0.33528 0.45084,-0.58268 0.7373,-0.74219 0.28646,-0.1595 0.62663,-0.23925 1.02051,-0.23926 0.39713,1e-5 0.73405,0.10092 1.01074,0.30274 0.27995,0.20183 0.48665,0.4948 0.62012,0.87891"
|
||||
style="font-size:10px;text-align:end;text-anchor:end;fill:#ffffff"
|
||||
@ -3527,40 +4018,43 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer36"
|
||||
inkscape:label="speed-window"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#000000;fill-opacity:0.25098039;fill-rule:evenodd;stroke:#ffffff;stroke-width:0.99991733;stroke-opacity:1;display:inline"
|
||||
id="speed-window"
|
||||
width="59.00008"
|
||||
height="214.00008"
|
||||
x="90.499962"
|
||||
y="71.999969"
|
||||
y="113.99997"
|
||||
inkscape:label="#rect6205" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer44"
|
||||
inkscape:label="speed-vector"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="speed-vector"
|
||||
width="5.5"
|
||||
height="106.5"
|
||||
x="143.5"
|
||||
y="72.499992"
|
||||
y="114.5"
|
||||
inkscape:label="#rect10011" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer19"
|
||||
inkscape:label="speed-scale"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="display:inline"
|
||||
id="speed-scale"
|
||||
inkscape:label="#g8377"
|
||||
transform="translate(84,10)">
|
||||
transform="translate(84,52)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path6219"
|
||||
@ -3683,11 +4177,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer35"
|
||||
inkscape:label="speed-box"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="speed-box"
|
||||
inkscape:label="#g10072"
|
||||
transform="translate(0,10)">
|
||||
transform="translate(0,52)">
|
||||
<path
|
||||
sodipodi:nodetypes="cccccccccc"
|
||||
inkscape:connector-curvature="0"
|
||||
@ -3707,10 +4202,11 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer47"
|
||||
inkscape:label="speed-waypoint"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:#bf00bf;fill-opacity:1;stroke:none"
|
||||
d="m 135.5,158 0,10.09375 8.5,9.40625 0,1.5 0,1.5 -8.5,9.40625 0,10.09375 13.5,0 0,-21 0,-21 -13.5,0 z"
|
||||
d="m 135.5,200 0,10.09375 8.5,9.40625 0,1.5 0,1.5 -8.5,9.40625 0,10.09375 13.5,0 0,-21 0,-21 -13.5,0 z"
|
||||
id="speed-waypoint"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path10065" />
|
||||
@ -3719,10 +4215,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer21"
|
||||
inkscape:label="speed-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;text-anchor:start;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="speed-text">
|
||||
id="speed-text"
|
||||
transform="translate(0,42)">
|
||||
<path
|
||||
d="m 97.728516,175.36133 c -0.609379,1e-5 -1.068362,0.30079 -1.376954,0.90234 -0.304689,0.59766 -0.457033,1.49805 -0.457031,2.70117 -2e-6,1.19923 0.152342,2.09962 0.457031,2.70118 0.308592,0.59765 0.767575,0.89648 1.376954,0.89648 0.613276,0 1.07226,-0.29883 1.376953,-0.89648 0.308588,-0.60156 0.462885,-1.50195 0.46289,-2.70118 -5e-6,-1.20312 -0.154302,-2.10351 -0.46289,-2.70117 -0.304693,-0.60155 -0.763677,-0.90233 -1.376953,-0.90234 m 0,-0.9375 c 0.980464,1e-5 1.72851,0.38868 2.24414,1.16601 0.519524,0.77345 0.779294,1.89845 0.779294,3.375 0,1.47266 -0.25977,2.59766 -0.779294,3.375 -0.51563,0.77344 -1.263676,1.16016 -2.24414,1.16016 -0.980472,0 -1.730471,-0.38672 -2.25,-1.16016 -0.515626,-0.77734 -0.773439,-1.90234 -0.773438,-3.375 -10e-7,-1.47655 0.257812,-2.60155 0.773438,-3.375 0.519529,-0.77733 1.269528,-1.166 2.25,-1.16601"
|
||||
style="font-size:12px;fill:#ffffff"
|
||||
@ -3762,10 +4260,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer1"
|
||||
inkscape:label="altitude-unit"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="altitude-unit">
|
||||
id="altitude-unit"
|
||||
transform="translate(0,42)">
|
||||
<path
|
||||
d="m 544.20056,290.91187 c 0.22461,-0.40365 0.49316,-0.7015 0.80567,-0.89356 0.31249,-0.19205 0.68033,-0.28808 1.10351,-0.28809 0.56965,1e-5 1.00911,0.20021 1.31836,0.60059 0.30924,0.39714 0.46386,0.96355 0.46387,1.69922 l 0,3.30078 -0.90332,0 0,-3.27148 c -10e-6,-0.52409 -0.0928,-0.91309 -0.27832,-1.167 -0.18556,-0.2539 -0.46876,-0.38085 -0.84961,-0.38086 -0.4655,1e-5 -0.83334,0.15463 -1.10352,0.46387 -0.27019,0.30925 -0.40528,0.7308 -0.40527,1.26465 l 0,3.09082 -0.90332,0 0,-3.27148 c -10e-6,-0.52734 -0.0928,-0.91634 -0.27832,-1.167 -0.18555,-0.2539 -0.47201,-0.38085 -0.85938,-0.38086 -0.45898,1e-5 -0.82357,0.15626 -1.09375,0.46875 -0.27018,0.30925 -0.40527,0.72917 -0.40527,1.25977 l 0,3.09082 -0.90332,0 0,-5.46875 0.90332,0 0,0.84961 c 0.20508,-0.33528 0.45084,-0.58268 0.7373,-0.74219 0.28646,-0.1595 0.62663,-0.23925 1.02051,-0.23926 0.39713,1e-5 0.73405,0.10092 1.01074,0.30274 0.27995,0.20183 0.48665,0.4948 0.62012,0.87891"
|
||||
style="font-size:10px;text-align:end;text-anchor:end;fill:#ffffff"
|
||||
@ -3777,37 +4277,40 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer32"
|
||||
inkscape:label="altitude-window"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#000000;fill-opacity:0.25098039;fill-rule:evenodd;stroke:#ffffff;stroke-width:0.99991733;stroke-opacity:1;display:inline"
|
||||
id="altitude-window"
|
||||
width="59.00008"
|
||||
height="214.00008"
|
||||
x="490.49994"
|
||||
y="71.999969"
|
||||
y="113.99997"
|
||||
inkscape:label="#rect6205" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer43"
|
||||
inkscape:label="altitude-vector"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#008000;fill-opacity:1;fill-rule:evenodd;stroke:none"
|
||||
id="altitude-vector"
|
||||
width="5.5"
|
||||
height="106.5"
|
||||
x="491"
|
||||
y="72.5"
|
||||
y="114.5"
|
||||
inkscape:label="#rect10008" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
inkscape:label="altitude-scale"
|
||||
id="g9764"
|
||||
inkscape:groupmode="layer">
|
||||
inkscape:groupmode="layer"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="matrix(-1,0,0,1,555.99999,10)"
|
||||
transform="matrix(-1,0,0,1,555.99999,52)"
|
||||
inkscape:label="#g8377"
|
||||
id="altitude-scale"
|
||||
style="display:inline">
|
||||
@ -3933,11 +4436,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer31"
|
||||
inkscape:label="altitude-box"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="altitude-box"
|
||||
inkscape:label="#g10076"
|
||||
transform="translate(0,10)">
|
||||
transform="translate(0,52)">
|
||||
<path
|
||||
inkscape:label="#path10043"
|
||||
sodipodi:nodetypes="cccccccccc"
|
||||
@ -3963,7 +4467,7 @@
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:#bf00bf;fill-opacity:1;stroke:none"
|
||||
d="m 491,158 0,21 0,21 15,0 0,-13.0625 -9.4375,-6.4375 0,-1.5 0,-1.5 L 506,171.0625 506,158 z"
|
||||
d="m 491,200 0,21 0,21 15,0 0,-13.0625 -9.4375,-6.4375 0,-1.5 0,-1.5 L 506,213.0625 506,200 z"
|
||||
id="altitude-waypoint"
|
||||
inkscape:label="#path10053"
|
||||
inkscape:connector-curvature="0"
|
||||
@ -3973,10 +4477,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer37"
|
||||
inkscape:label="altitude-text"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;text-align:end;line-height:125%;letter-spacing:0px;word-spacing:0px;text-anchor:end;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="altitude-text">
|
||||
id="altitude-text"
|
||||
transform="translate(0,42)">
|
||||
<path
|
||||
d="m 512.28516,175.36133 c -0.60938,1e-5 -1.06837,0.30079 -1.37696,0.90234 -0.30469,0.59766 -0.45703,1.49805 -0.45703,2.70117 0,1.19923 0.15234,2.09962 0.45703,2.70118 0.30859,0.59765 0.76758,0.89648 1.37696,0.89648 0.61327,0 1.07226,-0.29883 1.37695,-0.89648 0.30859,-0.60156 0.46288,-1.50195 0.46289,-2.70118 -10e-6,-1.20312 -0.1543,-2.10351 -0.46289,-2.70117 -0.30469,-0.60155 -0.76368,-0.90233 -1.37695,-0.90234 m 0,-0.9375 c 0.98046,1e-5 1.72851,0.38868 2.24414,1.16601 0.51952,0.77345 0.77929,1.89845 0.77929,3.375 0,1.47266 -0.25977,2.59766 -0.77929,3.375 -0.51563,0.77344 -1.26368,1.16016 -2.24414,1.16016 -0.98048,0 -1.73047,-0.38672 -2.25,-1.16016 -0.51563,-0.77734 -0.77344,-1.90234 -0.77344,-3.375 0,-1.47655 0.25781,-2.60155 0.77344,-3.375 0.51953,-0.77733 1.26952,-1.166 2.25,-1.16601"
|
||||
style="font-size:12px;fill:#ffffff"
|
||||
@ -4015,10 +4521,12 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer74"
|
||||
inkscape:label="vsi-unit"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="vsi-unit">
|
||||
id="vsi-unit"
|
||||
transform="translate(0.25011024,44)">
|
||||
<path
|
||||
d="m 561.48145,257.08456 0,0.74707 -0.85938,0 c -0.32227,10e-6 -0.54688,0.0651 -0.67383,0.19532 -0.1237,0.13021 -0.18555,0.36459 -0.18554,0.70312 l 0,0.4834 1.47949,0 0,0.69824 -1.47949,0 0,4.77051 -0.90333,0 0,-4.77051 -0.85937,0 0,-0.69824 0.85937,0 0,-0.38086 c 0,-0.60872 0.14161,-1.05142 0.42481,-1.32812 0.2832,-0.27994 0.73242,-0.41992 1.34766,-0.41993 l 0.84961,0"
|
||||
style="font-size:10px;text-align:end;text-anchor:end;fill:#ffffff"
|
||||
@ -4052,8 +4560,8 @@
|
||||
id="vsi-window"
|
||||
width="26.5"
|
||||
height="159"
|
||||
x="549.5"
|
||||
y="95.5"
|
||||
x="549.75012"
|
||||
y="137.5"
|
||||
inkscape:label="#rect9940" />
|
||||
</g>
|
||||
<g
|
||||
@ -4067,8 +4575,8 @@
|
||||
id="vsi-bar"
|
||||
width="5.5"
|
||||
height="79"
|
||||
x="550"
|
||||
y="96"
|
||||
x="550.25012"
|
||||
y="138"
|
||||
inkscape:label="#rect9943" />
|
||||
</g>
|
||||
<g
|
||||
@ -4079,7 +4587,8 @@
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="vsi-scale"
|
||||
inkscape:label="#g3460">
|
||||
inkscape:label="#g3460"
|
||||
transform="translate(0.25011024,42)">
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path9950"
|
||||
@ -4160,7 +4669,7 @@
|
||||
sodipodi:insensitive="true">
|
||||
<path
|
||||
style="fill:none;stroke:#ffffff;stroke-width:3.00000048;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline"
|
||||
d="m 549.99989,175 25.50022,0"
|
||||
d="m 550.25,217 25.50022,0"
|
||||
id="vsi-centerline"
|
||||
inkscape:connector-curvature="0"
|
||||
inkscape:label="#path9946" />
|
||||
@ -4176,22 +4685,23 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer68"
|
||||
inkscape:label="warnings-bg"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
transform="translate(0,-4)"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#ffffff;stroke-width:0.99988782;display:inline"
|
||||
style="fill:#000000;fill-opacity:1;fill-rule:evenodd;stroke:#ffffff;stroke-width:1.0059247;display:inline"
|
||||
id="warnings-bg"
|
||||
width="641.00012"
|
||||
height="17.000113"
|
||||
x="-0.50005609"
|
||||
y="467.49994"
|
||||
width="648.99408"
|
||||
height="16.994076"
|
||||
x="-4.4970379"
|
||||
y="463.50296"
|
||||
inkscape:label="#rect4736" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer51"
|
||||
inkscape:label="warning-autopilot"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="warning-autopilot"
|
||||
inkscape:label="#g4860">
|
||||
@ -4205,7 +4715,8 @@
|
||||
inkscape:label="#rect4824" />
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="warning-autopilot-label">
|
||||
id="warning-autopilot-label"
|
||||
transform="translate(0,0.73039)">
|
||||
<path
|
||||
d="m 393.41498,468.10666 -1.60547,4.35351 3.2168,0 -1.61133,-4.35351 m -0.66797,-1.16602 1.3418,0 3.33398,8.74805 -1.23047,0 -0.79687,-2.24414 -3.94336,0 -0.79688,2.24414 -1.24804,0 3.33984,-8.74805"
|
||||
style="font-size:12px;fill:#ffffff"
|
||||
@ -4258,7 +4769,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer29"
|
||||
inkscape:label="warning-master-caution"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="warning-master-caution"
|
||||
inkscape:label="#g4850">
|
||||
@ -4272,7 +4784,8 @@
|
||||
<g
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
id="warning-master-caution-label"
|
||||
inkscape:label="#warning-master-caution-label">
|
||||
inkscape:label="#warning-master-caution-label"
|
||||
transform="translate(-0.37041,0.11598)">
|
||||
<path
|
||||
d="m 267.67041,467.55505 1.76367,0 2.23242,5.95313 2.24414,-5.95313 1.76368,0 0,8.74805 -1.1543,0 0,-7.68164 -2.25586,6 -1.18945,0 -2.25586,-6 0,7.68164 -1.14844,0 0,-8.74805"
|
||||
style="font-size:12px;fill:#ffffff;-inkscape-font-specification:Sans"
|
||||
@ -4345,7 +4858,8 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer33"
|
||||
inkscape:label="warning-rc-input"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="warning-rc-input"
|
||||
inkscape:label="#g4855">
|
||||
@ -4402,30 +4916,34 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer34"
|
||||
inkscape:label="warning-attitude"
|
||||
style="display:inline">
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="warning-attitude"
|
||||
inkscape:label="#g4846">
|
||||
inkscape:label="#g4846"
|
||||
transform="translate(0,42)">
|
||||
<rect
|
||||
y="84.86544"
|
||||
x="259.71683"
|
||||
height="179.98485"
|
||||
width="119.27675"
|
||||
id="rect4817"
|
||||
style="fill:#ff0000;fill-opacity:0.49803922;fill-rule:evenodd;stroke:none" />
|
||||
style="fill:#ff0000;fill-opacity:0.49803922;fill-rule:evenodd;stroke:none"
|
||||
ry="5.1819358"
|
||||
rx="5.1819358" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4819"
|
||||
d="M 262.44093,87.080517 377.34003,263.25707"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:6;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="M 263.58049,88.871256 374.85741,260.61166"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:6;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff0000;stroke-width:6;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 374.85741,88.871256 263.58049,260.61166"
|
||||
id="path4821"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
<path
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4821"
|
||||
d="M 377.08567,87.407948 262.37897,263.31989"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:5.99999952;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<text
|
||||
xml:space="preserve"
|
||||
style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Sans"
|
||||
@ -4448,24 +4966,24 @@
|
||||
style="display:inline"
|
||||
id="warning-battery"
|
||||
inkscape:label="#g4313"
|
||||
transform="matrix(0.99951655,0,0,0.99607681,551.00855,-3.8091684)">
|
||||
transform="matrix(0.99951655,0,0,1.532684,551.00855,-1.7168189)">
|
||||
<rect
|
||||
y="3.8860531"
|
||||
y="1.2"
|
||||
x="0"
|
||||
height="33.01899"
|
||||
width="89.062027"
|
||||
height="34.5"
|
||||
width="89"
|
||||
id="rect4402"
|
||||
style="fill:#ff0000;fill-opacity:0.50196078;fill-rule:evenodd;stroke:none" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4404"
|
||||
d="M 0.59336762,5.3458595 88.556546,35.428338"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="M 2.1088442,2.592752 86.716324,34.298858"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 88.526587,5.3345863 0.59336762,35.360698"
|
||||
id="path4406"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 86.716324,2.592752 2.1088442,34.298858"
|
||||
id="path4616"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
@ -4477,29 +4995,29 @@
|
||||
style="display:inline"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
transform="matrix(0.99951655,0,0,0.99607681,91.008546,-3.8091684)"
|
||||
transform="matrix(0.99951655,0,0,1.532684,91.008546,-1.7168189)"
|
||||
inkscape:label="#g4313"
|
||||
id="warning-telemetry"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:#ff0000;fill-opacity:0.50196078;fill-rule:evenodd;stroke:none"
|
||||
id="rect4377"
|
||||
width="89.062027"
|
||||
height="33.01899"
|
||||
width="88"
|
||||
height="34.5"
|
||||
x="0"
|
||||
y="3.8860531" />
|
||||
y="1.2" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 0.59336762,5.3458595 88.556546,35.428338"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 2.2773164,2.8500377 85.494821,34.130511"
|
||||
id="path4379"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4381"
|
||||
d="M 88.526587,5.3345863 0.59336762,35.360698"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
id="path4611"
|
||||
d="M 85.494821,2.8500377 2.2773164,34.130511"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:round;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
@ -4512,29 +5030,43 @@
|
||||
style="display:inline"
|
||||
id="warning-gps"
|
||||
inkscape:label="#g4313"
|
||||
transform="matrix(0.99951655,0,0,0.99607681,0.008546,-3.8091684)">
|
||||
transform="matrix(0.99951655,0,0,1.532684,0.008546,-1.7168189)">
|
||||
<rect
|
||||
y="3.8860531"
|
||||
y="1.2"
|
||||
x="0"
|
||||
height="33.01899"
|
||||
width="89.062027"
|
||||
height="34.5"
|
||||
width="89"
|
||||
id="rect3539"
|
||||
style="fill:#ff0000;fill-opacity:0.50196078;fill-rule:evenodd;stroke:none" />
|
||||
<path
|
||||
sodipodi:nodetypes="cc"
|
||||
inkscape:connector-curvature="0"
|
||||
id="path4309"
|
||||
d="M 0.59336762,5.3458595 88.556546,35.428338"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" />
|
||||
d="M 2.3796722,2.8075235 86.665165,34.123438"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00634193;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" />
|
||||
<path
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00662947;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1"
|
||||
d="M 88.526587,5.3345863 0.59336762,35.360698"
|
||||
id="path4311"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:3.00634193;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
d="M 86.665165,2.8075235 2.3796722,34.123438"
|
||||
id="path4607"
|
||||
inkscape:connector-curvature="0"
|
||||
sodipodi:nodetypes="cc" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer69"
|
||||
inkscape:label="foreground_layer"
|
||||
sodipodi:insensitive="true"
|
||||
style="display:inline">
|
||||
<rect
|
||||
style="fill:none;stroke:none"
|
||||
id="foreground"
|
||||
width="641.5"
|
||||
height="481.5"
|
||||
x="-0.5"
|
||||
y="-0.5" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer13"
|
||||
@ -4543,12 +5075,12 @@
|
||||
transform="translate(0,-4)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:none;stroke:#ff0000;stroke-width:0.99999994;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;display:inline"
|
||||
style="fill:none;stroke:#ff0000;stroke-width:0;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;display:inline"
|
||||
id="pfd-window"
|
||||
width="641"
|
||||
height="481.00003"
|
||||
x="-0.5"
|
||||
y="3.4999695"
|
||||
width="642"
|
||||
height="486"
|
||||
x="-1"
|
||||
y="-1"
|
||||
inkscape:label="#rect4738" />
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 367 KiB After Width: | Height: | Size: 403 KiB |
@ -62,7 +62,8 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWindow *parent) :
|
||||
"GCSTelemetryStats" <<
|
||||
"SystemAlarms" <<
|
||||
"NedAccel" <<
|
||||
"FlightBatteryState";
|
||||
"FlightBatteryState" <<
|
||||
"ActuatorDesired";
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
|
@ -125,7 +125,8 @@ HEADERS += \
|
||||
$$UAVOBJECT_SYNTHETICS/osdsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/waypoint.h \
|
||||
$$UAVOBJECT_SYNTHETICS/waypointactive.h \
|
||||
$$UAVOBJECT_SYNTHETICS/mpu6000settings.h
|
||||
$$UAVOBJECT_SYNTHETICS/mpu6000settings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/takeofflocation.h
|
||||
|
||||
SOURCES += \
|
||||
$$UAVOBJECT_SYNTHETICS/accelgyrosettings.cpp \
|
||||
@ -227,4 +228,5 @@ SOURCES += \
|
||||
$$UAVOBJECT_SYNTHETICS/osdsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/waypoint.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/waypointactive.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/mpu6000settings.cpp
|
||||
$$UAVOBJECT_SYNTHETICS/mpu6000settings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/takeofflocation.cpp
|
||||
|
@ -58,12 +58,14 @@ endif
|
||||
|
||||
ifeq ($(UNAME), Linux)
|
||||
ifeq ($(ARCH), x86_64)
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-amd64.tar.bz2
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x64-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x64-5.2.1.run.md5
|
||||
QT_SDK_ARCH := gcc_64
|
||||
else
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-i686.tar.bz2
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2
|
||||
ARM_SDK_MD5_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-linux-x86-5.2.1.run
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-linux-x86-5.2.1.run.md5
|
||||
QT_SDK_ARCH := gcc
|
||||
@ -71,12 +73,14 @@ ifeq ($(UNAME), Linux)
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz
|
||||
else ifeq ($(UNAME), Darwin)
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-mac.tar.bz2
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2/+md5
|
||||
QT_SDK_URL := "Please install native Qt 5.1.x SDK using package manager"
|
||||
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
|
||||
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz
|
||||
else ifeq ($(UNAME), Windows)
|
||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2
|
||||
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip
|
||||
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip/+md5
|
||||
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.2/5.2.1/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe
|
||||
QT_SDK_MD5_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-opensource-windows-x86-mingw48_opengl-5.2.1.exe.md5
|
||||
QT_SDK_ARCH := mingw48_32
|
||||
@ -90,7 +94,7 @@ endif
|
||||
GTEST_URL := http://wiki.openpilot.org/download/attachments/18612236/gtest-1.6.0.zip
|
||||
|
||||
# Changing PYTHON_DIR, also update it in ground/openpilotgcs/src/python.pri
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_7-2013q1
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_8-2014q1
|
||||
QT_SDK_DIR := $(TOOLS_DIR)/qt-5.2.1
|
||||
MINGW_DIR := $(QT_SDK_DIR)/Tools/mingw48_32
|
||||
PYTHON_DIR := $(QT_SDK_DIR)/Tools/mingw48_32/opt/bin
|
||||
@ -111,7 +115,7 @@ QT_SDK_PREFIX := $(QT_SDK_DIR)
|
||||
|
||||
BUILD_SDK_TARGETS := arm_sdk qt_sdk
|
||||
ifeq ($(UNAME), Windows)
|
||||
BUILD_SDK_TARGETS += mingw sdl python nsis openssl
|
||||
BUILD_SDK_TARGETS += sdl nsis openssl
|
||||
endif
|
||||
ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen
|
||||
|
||||
@ -275,39 +279,43 @@ endef
|
||||
# $(1) = tool name
|
||||
# $(2) = tool extract/build directory
|
||||
# $(3) = tool distribution URL
|
||||
# $(4) = tool distribution file
|
||||
# $(5) = optional extra build recipes template
|
||||
# $(6) = optional extra clean recipes template
|
||||
# $(4) = tool distribution MD5 URL
|
||||
# $(5) = tool distribution file
|
||||
# $(6) = optional extra build recipes template
|
||||
# $(7) = optional extra clean recipes template
|
||||
#
|
||||
##############################
|
||||
|
||||
|
||||
|
||||
define TOOL_INSTALL_TEMPLATE
|
||||
|
||||
.PHONY: $(addprefix $(1)_, install clean distclean)
|
||||
|
||||
$(1)_install: $(1)_clean | $(DL_DIR) $(TOOLS_DIR)
|
||||
|
||||
$(call DOWNLOAD_TEMPLATE,$(3),$(4),"$(3).md5")
|
||||
|
||||
$(if $(4), $(call DOWNLOAD_TEMPLATE,$(3),$(5),$(4)),$(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(3).md5"))
|
||||
|
||||
@$(ECHO) $(MSG_EXTRACTING) $$(call toprel, $(2))
|
||||
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
|
||||
$(if $(filter $(suffix $(4)), .zip),
|
||||
$(V1) $(UNZIP) $(UNZIP_SILENT) -d $$(call toprel, $(dir $(2))) $$(call toprel, $(DL_DIR)/$(4)),
|
||||
$(V1) $(TAR) $(TAR_OPTIONS) -C $$(call toprel, $(dir $(2))) -xf $$(call toprel, $(DL_DIR)/$(4))
|
||||
|
||||
$(if $(filter $(suffix $(5)), .zip),
|
||||
$(V1) $(UNZIP) $(UNZIP_SILENT) -d $$(call toprel, $(dir $(2))) $$(call toprel, $(DL_DIR)/$(5)),
|
||||
$(V1) $(TAR) $(TAR_OPTIONS) -C $$(call toprel, $(dir $(2))) -xf $$(call toprel, $(DL_DIR)/$(5))
|
||||
)
|
||||
|
||||
$(5)
|
||||
$(6)
|
||||
|
||||
$(1)_clean:
|
||||
@$(ECHO) $(MSG_CLEANING) $$(call toprel, $(2))
|
||||
$(V1) [ ! -d "$(2)" ] || $(RM) -rf "$(2)"
|
||||
|
||||
$(6)
|
||||
$(7)
|
||||
|
||||
$(1)_distclean:
|
||||
@$(ECHO) $(MSG_DISTCLEANING) $$(call toprel, $(DL_DIR)/$(4))
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(4)" ] || $(RM) "$(DL_DIR)/$(4)"
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(4).md5" ] || $(RM) "$(DL_DIR)/$(4).md5"
|
||||
@$(ECHO) $(MSG_DISTCLEANING) $$(call toprel, $(DL_DIR)/$(5))
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5)" ] || $(RM) "$(DL_DIR)/$(5)"
|
||||
$(V1) [ ! -f "$(DL_DIR)/$(5).md5" ] || $(RM) "$(DL_DIR)/$(5).md5"
|
||||
|
||||
endef
|
||||
|
||||
@ -453,9 +461,13 @@ endef
|
||||
# ARM SDK
|
||||
#
|
||||
##############################
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,arm_sdk,$(ARM_SDK_DIR),$(ARM_SDK_URL),$(notdir $(ARM_SDK_URL))))
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
#unfortunately zip package for this release is missing root directory, so adding / at the end of the path
|
||||
# so that template interpret last part as directory and use the full path
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,arm_sdk,$(ARM_SDK_DIR)/,$(ARM_SDK_URL),$(ARM_SDK_MD5_URL),$(notdir $(ARM_SDK_URL))))
|
||||
else
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,arm_sdk,$(ARM_SDK_DIR),$(ARM_SDK_URL),$(ARM_SDK_MD5_URL),$(notdir $(ARM_SDK_URL))))
|
||||
endif
|
||||
ifeq ($(shell [ -d "$(ARM_SDK_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export ARM_SDK_PREFIX := $(ARM_SDK_DIR)/bin/arm-none-eabi-
|
||||
else
|
||||
@ -471,7 +483,7 @@ arm_sdk_version:
|
||||
# Template to check ARM toolchain version before building targets
|
||||
define ARM_GCC_VERSION_CHECK_TEMPLATE
|
||||
if ! $(ARM_SDK_PREFIX)gcc --version --specs=nano.specs >/dev/null 2>&1; then \
|
||||
$(ECHO) $(MSG_NOTICE) Please install ARM toolchain 4.7+ using \'make arm_sdk_install\' && \
|
||||
$(ECHO) $(MSG_NOTICE) Please install ARM toolchain 4.8 2014q1 using \'make arm_sdk_install\' && \
|
||||
$(ECHO) $(MSG_NOTICE) Older ARM SDKs do not support new \'--specs=nano.specs\' option && \
|
||||
exit 1; \
|
||||
fi
|
||||
@ -600,7 +612,7 @@ python_version:
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,nsis,$(NSIS_DIR),$(NSIS_URL),$(notdir $(NSIS_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,nsis,$(NSIS_DIR),$(NSIS_URL),,$(notdir $(NSIS_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(NSIS_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export NSIS := $(NSIS_DIR)/makensis
|
||||
@ -624,7 +636,7 @@ endif
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,sdl,$(SDL_DIR),$(SDL_URL),$(notdir $(SDL_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,sdl,$(SDL_DIR),$(SDL_URL),,$(notdir $(SDL_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(SDL_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export SDL_DIR := $(SDL_DIR)
|
||||
@ -647,7 +659,7 @@ endif
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,openssl,$(OPENSSL_DIR),$(OPENSSL_URL),$(notdir $(OPENSSL_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,openssl,$(OPENSSL_DIR),$(OPENSSL_URL),,$(notdir $(OPENSSL_URL))))
|
||||
|
||||
ifeq ($(shell [ -d "$(OPENSSL_DIR)" ] && $(ECHO) "exists"), exists)
|
||||
export OPENSSL := "$(OPENSSL_DIR)/bin/openssl"
|
||||
@ -671,7 +683,7 @@ endif
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,uncrustify,$(UNCRUSTIFY_DIR),$(UNCRUSTIFY_URL),$(notdir $(UNCRUSTIFY_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,uncrustify,$(UNCRUSTIFY_DIR),$(UNCRUSTIFY_URL),,$(notdir $(UNCRUSTIFY_URL))))
|
||||
|
||||
else # Linux or Mac
|
||||
|
||||
@ -695,7 +707,7 @@ define UNCRUSTIFY_CLEAN_TEMPLATE
|
||||
-$(V1) [ ! -d "$(UNCRUSTIFY_DIR)" ] || $(RM) -rf "$(UNCRUSTIFY_DIR)"
|
||||
endef
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,uncrustify,$(UNCRUSTIFY_BUILD_DIR),$(UNCRUSTIFY_URL),$(notdir $(UNCRUSTIFY_URL)),$(UNCRUSTIFY_BUILD_TEMPLATE),$(UNCRUSTIFY_CLEAN_TEMPLATE)))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,uncrustify,$(UNCRUSTIFY_BUILD_DIR),$(UNCRUSTIFY_URL),,$(notdir $(UNCRUSTIFY_URL)),$(UNCRUSTIFY_BUILD_TEMPLATE),$(UNCRUSTIFY_CLEAN_TEMPLATE)))
|
||||
|
||||
endif
|
||||
|
||||
@ -719,7 +731,7 @@ uncrustify_version:
|
||||
|
||||
ifeq ($(UNAME), Windows)
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,doxygen,$(DOXYGEN_DIR),$(DOXYGEN_URL),$(notdir $(DOXYGEN_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,doxygen,$(DOXYGEN_DIR),$(DOXYGEN_URL),,$(notdir $(DOXYGEN_URL))))
|
||||
|
||||
else # Linux or Mac
|
||||
|
||||
@ -743,7 +755,7 @@ define DOXYGEN_CLEAN_TEMPLATE
|
||||
-$(V1) [ ! -d "$(DOXYGEN_DIR)" ] || $(RM) -rf "$(DOXYGEN_DIR)"
|
||||
endef
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,doxygen,$(DOXYGEN_BUILD_DIR),$(DOXYGEN_URL),$(notdir $(DOXYGEN_URL)),$(DOXYGEN_BUILD_TEMPLATE),$(DOXYGEN_CLEAN_TEMPLATE)))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,doxygen,$(DOXYGEN_BUILD_DIR),$(DOXYGEN_URL),,$(notdir $(DOXYGEN_URL)),$(DOXYGEN_BUILD_TEMPLATE),$(DOXYGEN_CLEAN_TEMPLATE)))
|
||||
|
||||
endif
|
||||
|
||||
@ -765,7 +777,7 @@ doxygen_version:
|
||||
#
|
||||
##############################
|
||||
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,gtest,$(GTEST_DIR),$(GTEST_URL),$(notdir $(GTEST_URL))))
|
||||
$(eval $(call TOOL_INSTALL_TEMPLATE,gtest,$(GTEST_DIR),$(GTEST_URL),,$(notdir $(GTEST_URL))))
|
||||
|
||||
export GTEST_DIR
|
||||
|
||||
|
@ -12,6 +12,8 @@
|
||||
|
||||
<field name="CourseFeedForward" units="s" type="float" elements="1" defaultvalue="3.0"/>
|
||||
<!-- how many seconds to plan the flight vector ahead when initiating necessary heading changes - increase for planes with sluggish response -->
|
||||
<field name="ReverseCourseOverlap" units="deg" type="float" elements="1" defaultvalue="20.0"/>
|
||||
<!-- how big the overlapping area behind the plane is, where, if the desired course lies behind, the current bank angle will determine if the plane goes left or right -->
|
||||
|
||||
<field name="HorizontalPosP" units="(m/s)/m" type="float" elements="1" defaultvalue="0.05"/>
|
||||
<!-- proportional coefficient for correction vector in path vector field to get back on course - reduce for fast planes to prevent course oscillations -->
|
||||
|
@ -7,69 +7,69 @@
|
||||
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
|
||||
<field name="Stabilization1Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Attitude,Attitude,AxisLock,Manual"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
<field name="Stabilization2Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Attitude,Attitude,Rate,Manual"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
<field name="Stabilization3Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Rate,Rate,Rate,Manual"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
<field name="Stabilization4Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Attitude,Attitude,AxisLock,CruiseControl"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
<field name="Stabilization5Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Attitude,Attitude,Rate,CruiseControl"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
<field name="Stabilization6Settings" units="" type="enum"
|
||||
elementnames="Roll,Pitch,Yaw,Thrust"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"
|
||||
options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"
|
||||
defaultvalue="Rate,Rate,Rate,CruiseControl"
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity:CruiseControl; \
|
||||
limits="%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario:CruiseControl; \
|
||||
%NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude,\
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:VerticalVelocity;"
|
||||
%0401NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario,\
|
||||
%0402NE:Rate:Attitude:AxisLock:WeakLeveling:VirtualBar:Rattitude:RelayRate:RelayAttitude:AltitudeHold:AltitudeVario;"
|
||||
/>
|
||||
|
||||
<!-- Note these options values should be identical to those defined in FlightMode -->
|
||||
@ -78,37 +78,42 @@
|
||||
units=""
|
||||
type="enum"
|
||||
elements="6"
|
||||
options="Manual,Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6,Autotune,PositionHold,ReturnToBase,Land,PathPlanner,POI"
|
||||
options="Manual,Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6,Autotune,PositionHold,PositionVarioFPV,PositionVarioLOS,PositionVarioNSEW,ReturnToBase,Land,PathPlanner,POI,AutoCruise"
|
||||
defaultvalue="Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6"
|
||||
limits="\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise;\
|
||||
\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise;\
|
||||
\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise;\
|
||||
\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise;\
|
||||
\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI;\
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise;\
|
||||
\
|
||||
%0401NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0402NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI,\
|
||||
%0903NE:Autotune:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>
|
||||
%0401NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0402NE:Autotune:PositionHold:PositionVarioFPV:PositionVarioLOS:PositionVarioNSEW:ReturnToBase:Land:PathPlanner:POI:AutoCruise,\
|
||||
%0903NE:Autotune:AutoCruise"/>
|
||||
|
||||
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
|
||||
<field name="ArmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>
|
||||
<field name="DisarmingSequenceTime" units="ms" type="uint16" elements="1" defaultvalue="1000"/>
|
||||
<field name="ReturnToHomeAltitudeOffset" units="m" type="float" elements="1" defaultvalue="10"/>
|
||||
<field name="ReturnToBaseAltitudeOffset" units="m" type="float" elements="1" defaultvalue="10"/>
|
||||
<field name="PositionHoldOffset" units="m" type="float" elementnames="Horizontal,Vertical" defaultvalue="10,2"/>
|
||||
<!-- optimized for current vtolpathfollower,
|
||||
for fixed wing pathfollower set to Horizontal=500,Vertical=5 -->
|
||||
<field name="PositionHoldStartingVelocity" units="m/s" type="float" elements="1" defaultvalue="20"/>
|
||||
<!-- currently ignored by vtolpathfollower -->
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
@ -4,7 +4,7 @@
|
||||
<field name="Armed" units="" type="enum" elements="1" options="Disarmed,Arming,Armed" defaultvalue="Disarmed"/>
|
||||
|
||||
<!-- Note these enumerated values should be the same as ManualControlSettings -->
|
||||
<field name="FlightMode" units="" type="enum" elements="1" options="Manual,Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6,Autotune,PositionHold,ReturnToBase,Land,PathPlanner,POI"/>
|
||||
<field name="FlightMode" units="" type="enum" elements="1" options="Manual,Stabilized1,Stabilized2,Stabilized3,Stabilized4,Stabilized5,Stabilized6,Autotune,PositionHold,PositionVarioFPV,PositionVarioLOS,PositionVarioNSEW,ReturnToBase,Land,PathPlanner,POI,AutoCruise"/>
|
||||
|
||||
<field name="ControlChain" units="bool" type="enum" options="false,true">
|
||||
<elementnames>
|
||||
|
@ -23,7 +23,7 @@
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="onchange" period="1000"/>
|
||||
<logging updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
@ -6,7 +6,7 @@
|
||||
<field name="Yaw" units="degrees" type="float" elements="1"/>
|
||||
<field name="Thrust" units="%" type="float" elements="1"/>
|
||||
<!-- These values should match those in FlightModeSettings.Stabilization{1,2,3}Settings -->
|
||||
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw,Thrust" options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,VerticalVelocity,CruiseControl"/>
|
||||
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw,Thrust" options="Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude,AltitudeHold,AltitudeVario,CruiseControl"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="1000"/>
|
||||
|
@ -3,7 +3,7 @@
|
||||
<description>Contains status information to control submodules for stabilization.</description>
|
||||
|
||||
|
||||
<field name="OuterLoop" units="" type="enum" options="Direct,Attitude,Rattitude,Weakleveling,Altitude,VerticalVelocity">
|
||||
<field name="OuterLoop" units="" type="enum" options="Direct,Attitude,Rattitude,Weakleveling,Altitude,AltitudeVario">
|
||||
<elementnames>
|
||||
<elementname>Roll</elementname>
|
||||
<elementname>Pitch</elementname>
|
||||
|
@ -45,8 +45,8 @@
|
||||
</elementnames>
|
||||
</field>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
14
shared/uavobjectdefinition/takeofflocation.xml
Normal file
14
shared/uavobjectdefinition/takeofflocation.xml
Normal file
@ -0,0 +1,14 @@
|
||||
<xml>
|
||||
<object name="TakeOffLocation" singleinstance="true" settings="true" category="Navigation">
|
||||
<description>TakeOffLocation setting which contains the destination of a ReturnToBase operation</description>
|
||||
<field name="North" units="m" type="float" elements="1" defaultvalue="0" />
|
||||
<field name="East" units="m" type="float" elements="1" defaultvalue="0" />
|
||||
<field name="Down" units="m" type="float" elements="1" defaultvalue="0" />
|
||||
<field name="Mode" units="" type="enum" elements="1" options="ArmingLocation,FirstArmingLocation,Preset" defaultvalue="ArmingLocation"/>
|
||||
<field name="Status" units="" type="enum" elements="1" options="Valid,Invalid" defaultvalue="Invalid"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
Loading…
x
Reference in New Issue
Block a user