@ -66,7 +66,6 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -66,7 +66,6 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// Do not allow changes here unless advanced is checked
ui . connectionType - > setEnabled ( false ) ;
ui . linkType - > setEnabled ( false ) ;
ui . protocolGroupBox - > setVisible ( false ) ;
ui . protocolTypeGroupBox - > setVisible ( false ) ;
@ -78,14 +77,19 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -78,14 +77,19 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
//connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.advancedOptionsCheckBox,SLOT(setChecked(bool)));
connect ( ui . advCheckBox , SIGNAL ( clicked ( bool ) ) , ui . protocolTypeGroupBox , SLOT ( setVisible ( bool ) ) ) ;
connect ( ui . advCheckBox , SIGNAL ( clicked ( bool ) ) , ui . connectionType , SLOT ( setEnabled ( bool ) ) ) ;
connect ( ui . advCheckBox , SIGNAL ( clicked ( bool ) ) , ui . linkType , SLOT ( setEnabled ( bool ) ) ) ;
connect ( ui . advCheckBox , SIGNAL ( clicked ( bool ) ) , ui . protocolGroupBox , SLOT ( setVisible ( bool ) ) ) ;
// add link types
ui . linkType - > addItem ( tr ( " Serial " ) , QGC_LINK_SERIAL ) ;
ui . linkType - > addItem ( tr ( " UDP " ) , QGC_LINK_UDP ) ;
ui . linkType - > addItem ( tr ( " Simulation " ) , QGC_LINK_SIMULATION ) ;
if ( dynamic_cast < MAVLinkSimulationLink * > ( link ) ) {
//Only show simulation option if already setup elsewhere as a simulation
ui . linkType - > addItem ( tr ( " Simulation " ) , QGC_LINK_SIMULATION ) ;
}
# ifdef OPAL_RT
ui . linkType - > addItem ( tr ( " Opal-RT Link " ) , QGC_LINK_OPAL ) ;
# endif
# ifdef XBEELINK
ui . linkType - > addItem ( tr ( " Xbee API " ) , QGC_LINK_XBEE ) ;
# endif // XBEELINK
@ -135,18 +139,19 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -135,18 +139,19 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
QWidget * conf = new SerialConfigurationWindow ( serial , this ) ;
ui . linkScrollArea - > setWidget ( conf ) ;
ui . linkGroupBox - > setTitle ( tr ( " Serial Link " ) ) ;
ui . linkType - > setCurrentIndex ( 0 ) ;
ui . linkType - > setCurrentIndex ( ui . linkType - > findData ( QGC_LINK_SERIAL ) ) ;
}
UDPLink * udp = dynamic_cast < UDPLink * > ( link ) ;
if ( udp ! = 0 ) {
QWidget * conf = new QGCUDPLinkConfiguration ( udp , this ) ;
ui . linkScrollArea - > setWidget ( conf ) ;
ui . linkGroupBox - > setTitle ( tr ( " UDP Link " ) ) ;
ui . linkType - > setCurrentIndex ( 1 ) ;
ui . linkType - > setCurrentIndex ( ui . linkType - > findData ( QGC_LINK_UDP ) ) ;
}
MAVLinkSimulationLink * sim = dynamic_cast < MAVLinkSimulationLink * > ( link ) ;
if ( sim ! = 0 ) {
ui . linkType - > setCurrentIndex ( 2 ) ;
ui . linkType - > setCurrentIndex ( ui . linkType - > findData ( QGC_LINK_SIMULATION ) ) ;
ui . linkType - > setEnabled ( false ) ; //Don't allow the user to change to a non-simulation
ui . linkGroupBox - > setTitle ( tr ( " MAVLink Simulation Link " ) ) ;
}
# ifdef OPAL_RT
@ -156,7 +161,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -156,7 +161,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
QBoxLayout * layout = new QBoxLayout ( QBoxLayout : : LeftToRight , ui . linkGroupBox ) ;
layout - > addWidget ( conf ) ;
ui . linkGroupBox - > setLayout ( layout ) ;
ui . linkType - > setCurrentIndex ( 3 ) ;
ui . linkType - > setCurrentIndex ( ui . linkType - > findData ( QGC_LINK_OPAL ) ) ;
ui . linkGroupBox - > setTitle ( tr ( " Opal-RT Link " ) ) ;
}
# endif
@ -167,7 +172,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -167,7 +172,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
QWidget * conf = new XbeeConfigurationWindow ( xbee , this ) ;
ui . linkScrollArea - > setWidget ( conf ) ;
ui . linkGroupBox - > setTitle ( tr ( " Xbee Link " ) ) ;
ui . linkType - > setCurrentIndex ( 4 ) ;
ui . linkType - > setCurrentIndex ( ui . linkType - > findData ( QGC_LINK_XBEE ) ) ;
connect ( xbee , SIGNAL ( tryConnectBegin ( bool ) ) , ui . actionConnect , SLOT ( setDisabled ( bool ) ) ) ;
connect ( xbee , SIGNAL ( tryConnectEnd ( bool ) ) , ui . actionConnect , SLOT ( setEnabled ( bool ) ) ) ;
}
@ -183,7 +188,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
@@ -183,7 +188,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
qDebug ( ) < < " Link is NOT a known link, can't open configuration window " ;
}
connect ( ui . linkType , SIGNAL ( currentIndexChanged ( int ) ) , this , SLOT ( setLinkType ( int ) ) ) ;
connect ( ui . linkType , SIGNAL ( currentIndexChanged ( int ) ) , this , SLOT ( linkCurrentIndexChanged ( int ) ) ) ;
// Open details pane for MAVLink if necessary
MAVLinkProtocol * mavlink = dynamic_cast < MAVLinkProtocol * > ( protocol ) ;
@ -213,7 +218,12 @@ QAction* CommConfigurationWindow::getAction()
@@ -213,7 +218,12 @@ QAction* CommConfigurationWindow::getAction()
return action ;
}
void CommConfigurationWindow : : setLinkType ( int linktype )
void CommConfigurationWindow : : linkCurrentIndexChanged ( int currentIndex )
{
setLinkType ( static_cast < qgc_link_t > ( ui . linkType - > itemData ( currentIndex ) . toInt ( ) ) ) ;
}
void CommConfigurationWindow : : setLinkType ( qgc_link_t linktype )
{
if ( link - > isConnected ( ) )
{
@ -230,7 +240,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
@@ -230,7 +240,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
switch ( linktype )
{
# ifdef XBEELINK
case 4 :
case QGC_LINK_XBEE :
{
XbeeLink * xbee = new XbeeLink ( ) ;
tmpLink = xbee ;
@ -238,7 +248,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
@@ -238,7 +248,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
break ;
}
# endif // XBEELINK
case 1 :
case QGC_LINK_UDP :
{
UDPLink * udp = new UDPLink ( ) ;
tmpLink = udp ;
@ -247,7 +257,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
@@ -247,7 +257,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
}
# ifdef OPAL_RT
case 3 :
case QGC_LINK_OPAL :
{
OpalLink * opal = new OpalLink ( ) ;
tmpLink = opal ;
@ -258,7 +268,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
@@ -258,7 +268,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
default :
{
}
case 0 :
case QGC_LINK_SERIAL :
{
SerialLink * serial = new SerialLink ( ) ;
tmpLink = serial ;