@ -7,12 +7,7 @@
@@ -7,12 +7,7 @@
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/// @file
/// @author Don Gagne <don@thegagnes.com>
# include "APMAirframeComponentController.h"
# include "APMAirframeComponentAirframes.h"
# include "QGCMAVLink.h"
# include "MultiVehicleManager.h"
# include "QGCApplication.h"
@ -26,71 +21,113 @@
@@ -26,71 +21,113 @@
# include <QJsonParseError>
# include <QJsonObject>
bool APMAirframeComponentController : : _typesRegistered = false ;
const char * APMAirframeComponentController : : _oldFrameParam = " FRAME " ;
const char * APMAirframeComponentController : : _newFrameParam = " FRAME_CLASS " ;
APMAirframeComponentController : : APMAirframeComponentController ( void ) :
_airframeTypesModel ( new QmlObjectListModel ( this ) )
{
if ( ! _typesRegistered ) {
_typesRegistered = true ;
qmlRegisterUncreatableType < APMAirframeType > ( " QGroundControl.Controllers " , 1 , 0 , " APMAirframeType " , QStringLiteral ( " Can only reference APMAirframeType " ) ) ;
}
_fillAirFrames ( ) ;
Fact * frame = NULL ;
if ( parameterExists ( FactSystem : : defaultComponentId , _oldFrameParam ) ) {
frame = getParameterFact ( FactSystem : : defaultComponentId , _oldFrameParam ) ;
} else if ( parameterExists ( FactSystem : : defaultComponentId , _newFrameParam ) ) {
frame = getParameterFact ( FactSystem : : defaultComponentId , _newFrameParam ) ;
// These should match the FRAME_CLASS parameter enum meta data
# define FRAME_CLASS_UNDEFINED 0
# define FRAME_CLASS_QUAD 1
# define FRAME_CLASS_HEX 2
# define FRAME_CLASS_OCTA 3
# define FRAME_CLASS_OCTAQUAD 4
# define FRAME_CLASS_Y6 5
# define FRAME_CLASS_HELI 6
# define FRAME_CLASS_TRI 7
# define FRAME_CLASS_SINGLECOPTER 8
# define FRAME_CLASS_COAXCOPTER 9
# define FRAME_CLASS_BICOPTER 10
# define FRAME_CLASS_HELI_DUAL 11
# define FRAME_CLASS_DODECAHEXA 12
# define FRAME_CLASS_HELIQUAD 13
// These should match the FRAME_TYPE parameter enum meta data
# define FRAME_TYPE_PLUS 0
# define FRAME_TYPE_X 1
# define FRAME_TYPE_V 2
# define FRAME_TYPE_H 3
# define FRAME_TYPE_V_TAIL 4
# define FRAME_TYPE_A_TAIL 5
# define FRAME_TYPE_Y6B 10
# define FRAME_TYPE_Y6F 11
# define FRAME_TYPE_BETAFLIGHTX 12
# define FRAME_TYPE_DJIX 13
# define FRAME_TYPE_CLOCKWISEX 14
typedef struct {
int frameClass ;
int frameType ;
const char * imageResource ;
} FrameToImageInfo_t ;
static const FrameToImageInfo_t s_rgFrameToImage [ ] = {
{ FRAME_CLASS_QUAD , FRAME_TYPE_PLUS , " QuadRotorPlus " } ,
{ FRAME_CLASS_QUAD , FRAME_TYPE_X , " QuadRotorX " } ,
{ FRAME_CLASS_QUAD , FRAME_TYPE_V , " QuadRotorWide " } ,
{ FRAME_CLASS_QUAD , FRAME_TYPE_H , " QuadRotorH " } ,
{ FRAME_CLASS_QUAD , FRAME_TYPE_V_TAIL , " QuadRotorVTail " } ,
{ FRAME_CLASS_QUAD , FRAME_TYPE_A_TAIL , " QuadRotorATail " } ,
{ FRAME_CLASS_HEX , FRAME_TYPE_PLUS , " HexaRotorPlus " } ,
{ FRAME_CLASS_HEX , FRAME_TYPE_X , " HexaRotorX " } ,
{ FRAME_CLASS_OCTA , FRAME_TYPE_PLUS , " OctoRotorPlus " } ,
{ FRAME_CLASS_OCTA , FRAME_TYPE_X , " OctoRotorX " } ,
{ FRAME_CLASS_OCTAQUAD , FRAME_TYPE_PLUS , " OctoRotorPlusCoaxial " } ,
{ FRAME_CLASS_OCTAQUAD , FRAME_TYPE_X , " OctoRotorXCoaxial " } ,
{ FRAME_CLASS_Y6 , FRAME_TYPE_Y6B , " Y6B " } ,
{ FRAME_CLASS_Y6 , FRAME_TYPE_Y6F , " AirframeUnknown " } ,
{ FRAME_CLASS_Y6 , - 1 , " Y6A " } ,
{ FRAME_CLASS_HELI , - 1 , " Helicopter " } ,
{ FRAME_CLASS_TRI , - 1 , " YPlus " } ,
} ;
static QString s_findImageResource ( int frameClass , int frameType )
{
for ( size_t i = 0 ; i < sizeof ( s_rgFrameToImage ) / sizeof ( s_rgFrameToImage [ 0 ] ) ; i + + ) {
const FrameToImageInfo_t * pFrameToImageInfo = & s_rgFrameToImage [ i ] ;
if ( pFrameToImageInfo - > frameClass = = frameClass & & pFrameToImageInfo - > frameType = = frameType ) {
return pFrameToImageInfo - > imageResource ;
} else if ( pFrameToImageInfo - > frameClass = = frameClass & & pFrameToImageInfo - > frameType = = - 1 ) {
return pFrameToImageInfo - > imageResource ;
}
}
if ( frame ) {
connect ( frame , & Fact : : rawValueChanged , this , & APMAirframeComponentController : : _factFrameChanged ) ;
_factFrameChanged ( frame - > rawValue ( ) ) ;
}
return QStringLiteral ( " AirframeUnknown " ) ;
}
APMAirframeComponentController : : ~ APMAirframeComponentController ( )
APMAirframeComponentController : : APMAirframeComponentController ( void )
: _frameClassFact ( getParameterFact ( FactSystem : : defaultComponentId , QStringLiteral ( " FRAME_CLASS " ) ) )
, _frameTypeFact ( getParameterFact ( FactSystem : : defaultComponentId , QStringLiteral ( " FRAME_TYPE " ) ) )
, _frameClassModel ( new QmlObjectListModel ( this ) )
{
_fillFrameClasses ( ) ;
}
void APMAirframeComponentController : : _factFrameChanged ( QVariant value )
APMAirframeComponentController : : ~ APMAirframeComponentController ( )
{
FrameId v = ( FrameId ) value . toInt ( ) ;
for ( int i = 0 , size = _airframeTypesModel - > count ( ) ; i < size ; i + + ) {
APMAirframeType * airframeType = qobject_cast < APMAirframeType * > ( _airframeTypesModel - > get ( i ) ) ;
Q_ASSERT ( airframeType ) ;
if ( airframeType - > type ( ) = = v ) {
_currentAirframeType = airframeType ;
break ;
}
}
emit currentAirframeTypeChanged ( _currentAirframeType ) ;
}
void APMAirframeComponentController : : _fillAirFrames ( )
void APMAirframeComponentController : : _fillFrameClasses ( )
{
for ( int tindex = 0 ; tindex < APMAirframeComponentAirframes : : get ( ) . count ( ) ; tindex + + ) {
const APMAirframeComponentAirframes : : AirframeType_t * pType = APMAirframeComponentAirframes : : get ( ) . values ( ) . at ( tindex ) ;
QList < int > frameTypeNotSupported ;
APMAirframeType * airframeType = new APMAirframeType ( pType - > name , pType - > imageResource , pType - > type , this ) ;
Q_CHECK_PTR ( airframeType ) ;
frameTypeNotSupported < < FRAME_CLASS_HELI
< < FRAME_CLASS_SINGLECOPTER
< < FRAME_CLASS_COAXCOPTER
< < FRAME_CLASS_BICOPTER
< < FRAME_CLASS_HELI_DUAL
< < FRAME_CLASS_HELIQUAD ;
for ( int index = 0 ; index < pType - > rgAirframeInfo . count ( ) ; index + + ) {
const APMAirframe * pInfo = pType - > rgAirframeInfo . at ( index ) ;
Q_CHECK_PTR ( pInfo ) ;
for ( int i = 1 ; i < _frameClassFact - > enumStrings ( ) . count ( ) ; i + + ) {
QString frameClassName = _frameClassFact - > enumStrings ( ) [ i ] ;
int frameClass = _frameClassFact - > enumValues ( ) [ i ] . toInt ( ) ;
int defaultFrameType ;
airframeType - > addAirframe ( pInfo - > name ( ) , pInfo - > params ( ) , pInfo - > type ( ) ) ;
if ( frameTypeNotSupported . contains ( frameClass ) ) {
defaultFrameType = - 1 ;
} else {
defaultFrameType = FRAME_TYPE_X ;
}
_airframeTypesModel - > append ( airframeType ) ;
_frameClas sModel - > append ( new APMFrameClass ( frameClassName , frameClass , _frameTypeFact , defaultFrameType , _frameClassModel ) ) ;
}
emit loadAirframesCompleted ( ) ;
}
void APMAirframeComponentController : : _loadParametersFromDownloadFile ( const QString & downloadedParamFile )
@ -120,86 +157,6 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri
@@ -120,86 +157,6 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri
_vehicle - > parameterManager ( ) - > refreshAllParameters ( ) ;
}
APMAirframeType : : APMAirframeType ( const QString & name , const QString & imageResource , int type , QObject * parent ) :
QObject ( parent ) ,
_name ( name ) ,
_imageResource ( imageResource ) ,
_type ( type ) ,
_dirty ( false )
{
}
APMAirframeType : : ~ APMAirframeType ( )
{
}
void APMAirframeType : : addAirframe ( const QString & name , const QString & file , int type )
{
APMAirframe * airframe = new APMAirframe ( name , file , type ) ;
Q_CHECK_PTR ( airframe ) ;
_airframes . append ( QVariant : : fromValue ( airframe ) ) ;
}
APMAirframe : : APMAirframe ( const QString & name , const QString & paramsFile , int type , QObject * parent ) :
QObject ( parent ) ,
_name ( name ) ,
_paramsFile ( paramsFile ) ,
_type ( type )
{
}
QString APMAirframe : : name ( ) const
{
return _name ;
}
QString APMAirframe : : params ( ) const
{
return _paramsFile ;
}
int APMAirframe : : type ( ) const
{
return _type ;
}
APMAirframe : : ~ APMAirframe ( )
{
}
QString APMAirframeType : : imageResource ( ) const
{
return _imageResource ;
}
QString APMAirframeType : : name ( ) const
{
return _name ;
}
int APMAirframeType : : type ( ) const
{
return _type ;
}
APMAirframeType * APMAirframeComponentController : : currentAirframeType ( ) const
{
return _currentAirframeType ;
}
QString APMAirframeComponentController : : currentAirframeTypeName ( ) const
{
return _vehicle - > vehicleTypeName ( ) ;
}
void APMAirframeComponentController : : setCurrentAirframeType ( APMAirframeType * t )
{
Fact * param = getParameterFact ( - 1 , QStringLiteral ( " FRAME " ) ) ;
Q_ASSERT ( param ) ;
param - > setRawValue ( t - > type ( ) ) ;
}
void APMAirframeComponentController : : loadParameters ( const QString & paramFile )
{
qgcApp ( ) - > setOverrideCursor ( Qt : : WaitCursor ) ;
@ -258,3 +215,25 @@ void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg)
@@ -258,3 +215,25 @@ void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg)
qgcApp ( ) - > showMessage ( tr ( " Param file download failed: %1 " ) . arg ( errorMsg ) ) ;
qgcApp ( ) - > restoreOverrideCursor ( ) ;
}
APMFrameClass : : APMFrameClass ( const QString & name , int frameClass , Fact * frameTypeFact , int defaultFrameType , QObject * parent )
: QObject ( parent )
, _name ( name )
, _frameClass ( frameClass )
, _defaultFrameType ( defaultFrameType )
, _frameTypeSupported ( defaultFrameType ! = - 1 )
, _frameTypeFact ( frameTypeFact )
{
connect ( frameTypeFact , & Fact : : rawValueChanged , this , & APMFrameClass : : imageResourceChanged ) ;
connect ( frameTypeFact , & Fact : : rawValueChanged , this , & APMFrameClass : : frameTypeChanged ) ;
}
APMFrameClass : : ~ APMFrameClass ( )
{
}
QString APMFrameClass : : imageResource ( void )
{
return QStringLiteral ( " /qmlimages/Airframe/%1 " ) . arg ( s_findImageResource ( _frameClass , _frameTypeFact - > rawValue ( ) . toInt ( ) ) ) ;
}