@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
@@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
commStatus ( COMM_DISCONNECTED ) ,
receiveDropRate ( 0 ) ,
sendDropRate ( 0 ) ,
statusTimeout ( new QTimer ( this ) ) ,
statusTimeout ( thread ) ,
name ( " " ) ,
type ( MAV_TYPE_GENERIC ) ,
@ -164,12 +164,10 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
@@ -164,12 +164,10 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
hilEnabled ( false ) ,
sensorHil ( false ) ,
lastSendTimeGPS ( 0 ) ,
lastSendTimeSensors ( 0 )
lastSendTimeSensors ( 0 ) ,
_thread ( thread )
{
moveToThread ( thread ) ;
waypointManager . moveToThread ( thread ) ;
paramMgr . moveToThread ( thread ) ;
statusTimeout - > moveToThread ( thread ) ;
for ( unsigned int i = 0 ; i < 255 ; + + i )
{
@ -180,66 +178,66 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
@@ -180,66 +178,66 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
// Store a list of available actions for this UAS.
// Basically everything exposed as a SLOT with no return value or arguments.
QAction * newAction = new QAction ( tr ( " Arm " ) , this ) ;
QAction * newAction = new QAction ( tr ( " Arm " ) , thread ) ;
newAction - > setToolTip ( tr ( " Enable the UAS so that all actuators are online " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( armSystem ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Disarm " ) , this ) ;
newAction = new QAction ( tr ( " Disarm " ) , thread ) ;
newAction - > setToolTip ( tr ( " Disable the UAS so that all actuators are offline " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( disarmSystem ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Toggle armed " ) , this ) ;
newAction = new QAction ( tr ( " Toggle armed " ) , thread ) ;
newAction - > setToolTip ( tr ( " Toggle between armed and disarmed " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( toggleAutonomy ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Go home " ) , this ) ;
newAction = new QAction ( tr ( " Go home " ) , thread ) ;
newAction - > setToolTip ( tr ( " Command the UAS to return to its home position " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( home ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Land " ) , this ) ;
newAction = new QAction ( tr ( " Land " ) , thread ) ;
newAction - > setToolTip ( tr ( " Command the UAS to land " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( land ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Launch " ) , this ) ;
newAction = new QAction ( tr ( " Launch " ) , thread ) ;
newAction - > setToolTip ( tr ( " Command the UAS to launch itself and begin its mission " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( launch ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Resume " ) , this ) ;
newAction = new QAction ( tr ( " Resume " ) , thread ) ;
newAction - > setToolTip ( tr ( " Command the UAS to continue its mission " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( go ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Stop " ) , this ) ;
newAction = new QAction ( tr ( " Stop " ) , thread ) ;
newAction - > setToolTip ( tr ( " Command the UAS to halt and hold position " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( halt ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Go autonomous " ) , this ) ;
newAction = new QAction ( tr ( " Go autonomous " ) , thread ) ;
newAction - > setToolTip ( tr ( " Set the UAS into an autonomous control mode " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( goAutonomous ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Go manual " ) , this ) ;
newAction = new QAction ( tr ( " Go manual " ) , thread ) ;
newAction - > setToolTip ( tr ( " Set the UAS into a manual control mode " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( goManual ( ) ) ) ;
actions . append ( newAction ) ;
newAction = new QAction ( tr ( " Toggle autonomy " ) , this ) ;
newAction = new QAction ( tr ( " Toggle autonomy " ) , thread ) ;
newAction - > setToolTip ( tr ( " Toggle between manual and full-autonomy " ) ) ;
connect ( newAction , SIGNAL ( triggered ( ) ) , this , SLOT ( toggleAutonomy ( ) ) ) ;
actions . append ( newAction ) ;
color = UASInterface : : getNextColor ( ) ;
setBatterySpecs ( QString ( " " ) ) ;
connect ( statusTimeout , SIGNAL ( timeout ( ) ) , this , SLOT ( updateState ( ) ) ) ;
connect ( & statusTimeout , SIGNAL ( timeout ( ) ) , this , SLOT ( updateState ( ) ) ) ;
connect ( this , SIGNAL ( systemSpecsChanged ( int ) ) , this , SLOT ( writeSettings ( ) ) ) ;
statusTimeout - > start ( 500 ) ;
statusTimeout . start ( 500 ) ;
readSettings ( ) ;
//need to init paramMgr after readSettings have been loaded, to properly set autopilot and so forth
paramMgr . initWithUAS ( this ) ;
@ -255,8 +253,11 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
@@ -255,8 +253,11 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
UAS : : ~ UAS ( )
{
writeSettings ( ) ;
_thread - > quit ( ) ;
_thread - > wait ( ) ;
delete links ;
delete statusTimeout ;
delete simulation ;
}