Commit 5f00eab1 authored by pixhawk's avatar pixhawk

Fixed issue in simulation link

parent 5dad474e
......@@ -154,12 +154,12 @@ void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg)
unsigned int bufferlength = mavlink_msg_to_send_buffer(buf, msg);
// Pack to link buffer
// readyBufferMutex.lock();
readyBufferMutex.lock();
for (unsigned int i = 0; i < bufferlength; i++)
{
readyBuffer.enqueue(*(buf + i));
}
// readyBufferMutex.unlock();
readyBufferMutex.unlock();
}
void MAVLinkSimulationLink::enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg)
......@@ -891,8 +891,7 @@ void MAVLinkSimulationLink::readBytes() {
readyBufferMutex.lock();
const qint64 maxLength = 2048;
char data[maxLength];
qint64 len = maxLength;
if (maxLength > readyBuffer.size()) len = readyBuffer.size();
qint64 len = qMin((qint64)readyBuffer.size(), maxLength);
for (unsigned int i = 0; i < len; i++)
{
......
This diff is collapsed.
#ifndef WAYPOINTGLOBALVIEW_H
#define WAYPOINTGLOBALVIEW_H
#include <QWidget>
#include "Waypoint.h"
namespace Ui {
class WaypointGlobalView;
}
class WaypointGlobalView : public QWidget
{
Q_OBJECT
public:
explicit WaypointGlobalView(Waypoint* wp, QWidget *parent = 0);
~WaypointGlobalView();
public slots:
void updateValues(void);
void remove();
QString getLatitudString(float lat);
QString getLongitudString(float lon);
void getLatitudeGradoMin(float lat, int *gradoLat, float *minLat, QString *dirLat);
void getLongitudGradoMin(float lon, int *gradoLon, float *minLon, QString *dirLon);
void changeOrbitalState(int state);
void updateCoordValues(float lat, float lon);
//update latitude
void updateLatitudeWP(int value);
void updateLatitudeMinuteWP(double value);
void changeDirectionLatitudeWP();
//update longitude
void updateLongitudeWP(int value);
void updateLongitudeMinuteWP(double value);
void changeDirectionLongitudeWP();
signals:
void removeWaypoint(Waypoint*);
void changePositionWP(Waypoint*);
protected:
virtual void changeEvent(QEvent *e);
Waypoint* wp;
private:
Ui::WaypointGlobalView *ui;
private slots:
};
#endif // WAYPOINTGLOBALVIEW_H
This diff is collapsed.
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