Commit a61aead3 authored by Don Gagne's avatar Don Gagne

New LinkManager::[connect|disconnect]Link usage

parent 4d92b1d3
...@@ -853,7 +853,7 @@ void MAVLinkSimulationLink::readBytes() ...@@ -853,7 +853,7 @@ void MAVLinkSimulationLink::readBytes()
* @return True if connection has been disconnected, false if connection * @return True if connection has been disconnected, false if connection
* couldn't be disconnected. * couldn't be disconnected.
**/ **/
bool MAVLinkSimulationLink::disconnect() bool MAVLinkSimulationLink::_disconnect(void)
{ {
if(isConnected()) if(isConnected())
...@@ -877,7 +877,7 @@ bool MAVLinkSimulationLink::disconnect() ...@@ -877,7 +877,7 @@ bool MAVLinkSimulationLink::disconnect()
* @return True if connection has been established, false if connection * @return True if connection has been established, false if connection
* couldn't be established. * couldn't be established.
**/ **/
bool MAVLinkSimulationLink::connect() bool MAVLinkSimulationLink::_connect(void)
{ {
_isConnected = true; _isConnected = true;
emit connected(); emit connected();
...@@ -892,36 +892,6 @@ bool MAVLinkSimulationLink::connect() ...@@ -892,36 +892,6 @@ bool MAVLinkSimulationLink::connect()
return true; return true;
} }
/**
* Connect the link.
*
* @param connect true connects the link, false disconnects it
* @return True if connection has been established, false if connection
* couldn't be established.
**/
void MAVLinkSimulationLink::connectLink()
{
this->connect();
}
/**
* Connect the link.
*
* @param connect true connects the link, false disconnects it
* @return True if connection has been established, false if connection
* couldn't be established.
**/
bool MAVLinkSimulationLink::connectLink(bool connect)
{
_isConnected = connect;
if(connect) {
this->connect();
}
return true;
}
/** /**
* Check if connection is active. * Check if connection is active.
* *
......
...@@ -54,8 +54,6 @@ public: ...@@ -54,8 +54,6 @@ public:
void run(); void run();
void requestReset() { } void requestReset() { }
bool connect();
bool disconnect();
// Extensive statistics for scientific purposes // Extensive statistics for scientific purposes
qint64 getConnectionSpeed() const; qint64 getConnectionSpeed() const;
...@@ -71,13 +69,16 @@ public: ...@@ -71,13 +69,16 @@ public:
int getDataBitsType() const; int getDataBitsType() const;
int getStopBitsType() const; int getStopBitsType() const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
public slots: public slots:
void writeBytes(const char* data, qint64 size); void writeBytes(const char* data, qint64 size);
void readBytes(); void readBytes();
/** @brief Mainloop simulating the mainloop of the MAV */ /** @brief Mainloop simulating the mainloop of the MAV */
virtual void mainloop(); virtual void mainloop();
bool connectLink(bool connect);
void connectLink();
void sendMAVLinkMessage(const mavlink_message_t* msg); void sendMAVLinkMessage(const mavlink_message_t* msg);
...@@ -130,6 +131,10 @@ signals: ...@@ -130,6 +131,10 @@ signals:
void valueChanged(int uasId, QString curve, double value, quint64 usec); void valueChanged(int uasId, QString curve, double value, quint64 usec);
void messageReceived(const mavlink_message_t& message); void messageReceived(const mavlink_message_t& message);
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
}; };
#endif // MAVLINKSIMULATIONLINK_H #endif // MAVLINKSIMULATIONLINK_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment