Commit 2835885e authored by hengli's avatar hengli

Merge branch 'master' of pixhawk.ethz.ch:qgroundcontrol

parents fdc8d522 15caabd1
......@@ -51,11 +51,38 @@ OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
MAVLINK_CONF = ""
exists(user_config.pri) {
message("----- USING USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
include(user_config.pri)
}
INCLUDEPATH += $$BASEDIR/../mavlink/include/common
contains(MAVLINK_CONF, pixhawk) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
}
contains(MAVLINK_CONF, slugs) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
}
contains(MAVLINK_CONF, ualberta) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
}
# }
# Include general settings for MAVGround
......@@ -75,8 +102,7 @@ DEPENDPATH += . \
plugins
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/include \
$$BASEDIR/../mavlink/include/common
$$BASEDIR/../mavlink/include
# ../mavlink/include \
# MAVLink/include \
......@@ -193,6 +219,12 @@ HEADERS += src/MG.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/ui/WaypointGlobalView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/CheetahModel.h \
src/ui/map3D/CheetahGL.h \
......@@ -266,6 +298,12 @@ SOURCES += src/main.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/WaypointGlobalView.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/CheetahModel.cc \
......@@ -279,7 +317,7 @@ SOURCES += src/main.cc \
RESOURCES = mavground.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h) {
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:\OPAL-RT\RT-LAB7.2.4\Common\bin) {
message("Building support for Opal-RT")
LIBS += -LC:\OPAL-RT\RT-LAB7.2.4\Common\bin \
-lOpalApi
......
......@@ -2,9 +2,9 @@
<!-- Parameters in the top level block -->
<Block name="TopLevel">
<Parameter>
</Parameter>
</Block>
<!--Parameters related to the navigation block -->
......@@ -23,6 +23,117 @@
<!-- Paremters for the Pilot Input/Raw RC block -->
<Block name="ServoInputs">
<!-- Settings for Aileron Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="AIL_RIGHT_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="AIL_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="AIL_LEFT_IN"
/>
<!-- Settings for Elevator Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="ELE_DOWN_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="ELE_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="ELE_UP_IN"
/>
<!-- Settings for Throttle Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="THR_SET0_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="THR_SET1_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="THR_SET2_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint3"
QGCParamID="THR_SET3_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint4"
QGCParamID="THR_SET4_IN"
/>
<!-- Settings for Rudder Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="RUD_LEFT_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="RUD_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="RUD_RIGHT_IN"
/>
<!-- Settings for Gyro Mode/Gain Switch -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/GyroInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="GYRO_DEF_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/GyroInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="GYRO_TOG_IN"
/>
<!-- Settings for Pitch Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="PIT_SET0_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="PIT_SET1_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="PIT_SET2_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint3"
QGCParamID="PIT_SET3_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint4"
QGCParamID="PIT_SET4_IN"
/>
</Block>
......
<!-- Values are ordered low center high -->
<channels>
<threeSetpoint name="Aileron" number="1">1000.0, 1500.0, 2000.0</threeSetpoint>
<threeSetpoint name="Elevator" number="2">1000.0, 1500.0, 2000.0</threeSetpoint>
<threeSetpoint name="Rudder" number="4">1000.0, 1500.0, 2000.0</threeSetpoint>
<twoSetpoint name="Gyro" number="5">2000.0, 1000.0</twoSetpoint>
<fiveSetpoint name="Pitch" number="6">1000.0, 1250.0, 1500.0, 1750.0, 2000.0</fiveSetpoint>
<fiveSetpoint name="Throttle" number="3">1000.0, 1250.0, 1500.0, 1750.0, 2000.0</fiveSetpoint>
</channels>
......@@ -182,7 +182,7 @@ void MAVLinkSimulationLink::mainloop()
mavlink_attitude_t attitude;
memset(&attitude, 0, sizeof(mavlink_attitude_t));
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_raw_aux_t rawAuxValues;
memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
......@@ -305,7 +305,7 @@ void MAVLinkSimulationLink::mainloop()
{
rawImuValues.zgyro = d;
}
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
if (keys.value(i, "") == "Pressure")
{
rawAuxValues.baro = d;
......@@ -468,7 +468,7 @@ void MAVLinkSimulationLink::mainloop()
static int detectionCounter = 6;
if (detectionCounter % 10 == 0)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_pattern_detected_t detected;
detected.confidence = 5.0f;
......@@ -582,7 +582,7 @@ void MAVLinkSimulationLink::mainloop()
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
#endif
......@@ -619,7 +619,7 @@ void MAVLinkSimulationLink::mainloop()
//qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer;
// AUX STATUS
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
rawAuxValues.vbat = voltage;
#endif
......@@ -760,14 +760,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
}
break;
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_MANUAL_CONTROL:
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_manual_control_t control;
mavlink_msg_manual_control_decode(&msg, &control);
qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
#endif
}
break;
#endif
......
This diff is collapsed.
......@@ -152,6 +152,9 @@ protected:
unsigned short opalInstID;
uint16_t duty2PulseMicros(double duty);
uint8_t rescaleNorm(double norm, int ch);
bool sendRCValues;
};
#endif // OPALLINK_H
......@@ -41,7 +41,7 @@ namespace OpalRT
Configuration info for the model
*/
const unsigned short NUM_OUTPUT_SIGNALS=57;
const unsigned short NUM_OUTPUT_SIGNALS=42;
/* ------------------------------ Outputs ------------------------------
*
......@@ -86,7 +86,7 @@ namespace OpalRT
B_W_0,
B_W_1,
B_W_2,
RAW_CHANNEL_1 = 39,
RAW_CHANNEL_1 = 24,
RAW_CHANNEL_2,
RAW_CHANNEL_3,
RAW_CHANNEL_4,
......
......@@ -32,7 +32,8 @@ using namespace OpalRT;
ParameterList::ParameterList()
:params(new QMap<int, QMap<QGCParamID, Parameter> >),
paramList(new QList<QList<Parameter*> >())
paramList(new QList<QList<Parameter*> >()),
reqdServoParams(new QStringList())
{
QDir settingsDir = QDir(qApp->applicationDirPath());
......@@ -40,40 +41,20 @@ ParameterList::ParameterList()
settingsDir.cdUp();
settingsDir.cd("settings");
// Enforce a list of parameters which are necessary for flight
reqdServoParams->append("AIL_RIGHT_IN");
reqdServoParams->append("AIL_CENTER_IN");
reqdServoParams->append("AIL_LEFT_IN");
reqdServoParams->append("ELE_DOWN_IN");
reqdServoParams->append("ELE_CENTER_IN");
reqdServoParams->append("ELE_UP_IN");
reqdServoParams->append("RUD_LEFT_IN");
reqdServoParams->append("RUD_CENTER_IN");
reqdServoParams->append("RUD_RIGHT_IN");
QString filename(settingsDir.path() + "/ParameterList.xml");
if ((QFile::exists(filename)) && open(filename))
{
/* Populate the map with parameter names. There is no elegant way of doing this so all
parameter paths and names must be known at compile time and defined here.
Note: This function is written in a way that calls a lot of copy constructors and is
therefore not particularly efficient. However since it is only called once memory
and computation time are sacrificed for code clarity when adding and modifying
parameters.
When defining the path, the trailing slash is necessary
*/
// Parameter *p;
// /* Component: Navigation Filter */
// p = new Parameter("avionics_src/sm_ampro/NAV_FILT_INIT/",
// "Value",
// OpalRT::NAV_ID,
// QGCParamID("NAV_FILT_INIT"));
// (*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p);
// delete p;
//
// p = new Parameter("avionics_src/sm_ampro/Gain/",
// "Gain",
// OpalRT::NAV_ID,
// QGCParamID("TEST_OUTP_GAIN"));
// (*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p);
// delete p;
//
// /* Component: Log Facility */
// p = new Parameter("avionics_src/sm_ampro/LOG_FILE_ON/",
// "Value",
// OpalRT::LOG_ID,
// QGCParamID("LOG_FILE_ON"));
// (*params)[OpalRT::LOG_ID].insert(p->getParamID(), *p);
// delete p;
/* Get a list of the available parameters from opal-rt */
QMap<QString, unsigned short> *opalParams = new QMap<QString, unsigned short>;
......@@ -271,6 +252,8 @@ bool ParameterList::open(QString filename)
read(&paramFile);
paramFile.close();
return true;
}
......@@ -336,11 +319,25 @@ void ParameterList::parseBlock(const QDomElement &block)
static_cast<uint8_t>(id),
QGCParamID(e.attribute("QGCParamID")));
(*params)[id].insert(p->getParamID(), *p);
if (reqdServoParams->contains((QString)p->getParamID()))
reqdServoParams->removeAt(reqdServoParams->indexOf((QString)p->getParamID()));
delete p;
}
}
else
{
qDebug() << __FILE__ << ":" << __LINE__ << ": error in xml doc";
qDebug() << __FILE__ << ":" << __LINE__ << ": error in xml doc in block" << block.attribute("name");
}
}
if (!reqdServoParams->empty())
{
qDebug() << __FILE__ << __LINE__ << "Missing the following required servo parameters";
foreach(QString s, *reqdServoParams)
{
qDebug() << s;
}
}
......
......@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDir>
#include <QApplication>
#include <QtXml>
#include <QStringList>
#include "mavlink_types.h"
#include "QGCParamID.h"
......@@ -119,6 +120,10 @@ namespace OpalRT
are made through the map container.
*/
QList<QList<Parameter*> > *paramList;
/**
List of parameters which are necessary to control the servos.
*/
QStringList *reqdServoParams;
/**
Get the list of available parameters from Opal-RT.
\param[out] opalParams Map of parameter paths/names to ids which are valid in Opal-RT
......
......@@ -49,4 +49,6 @@ This file is part of the QGROUNDCONTROL project
#include <ardupilot.h>
#endif
#endif // QGCMAVLINK_H
......@@ -46,7 +46,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
if (message.sysid == uasId)
{
......@@ -169,7 +169,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_watchdog_command_t payload;
payload.target_system_id = uasId;
payload.watchdog_id = watchdogId;
......
......@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
}
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
#ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_CPU_LOAD:
{
......
......@@ -556,7 +556,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, severity, text);
}
break;
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES
#ifdef MAVLINK_ENABLED_UALBERTA
case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{
mavlink_nav_filter_bias_t bias;
......@@ -570,6 +570,41 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
}
break;
case MAVLINK_MSG_ID_RADIO_CALIBRATION:
{
mavlink_radio_calibration_t radioMsg;
mavlink_msg_radio_calibration_decode(&message, &radioMsg);
QVector<float> aileron;
QVector<float> elevator;
QVector<float> rudder;
QVector<float> gyro;
QVector<float> pitch;
QVector<float> throttle;
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
aileron << radioMsg.aileron[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
elevator << radioMsg.elevator[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
rudder << radioMsg.rudder[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
gyro << radioMsg.gyro[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
pitch << radioMsg.pitch[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
throttle << radioMsg.throttle[i];
QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron,
elevator,
rudder,
gyro,
pitch,
throttle);
emit radioCalibrationReceived(radioData);
delete radioData;
}
break;
#endif
default:
{
......@@ -588,7 +623,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
sendMessage(msg);
......@@ -597,7 +632,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg);
......@@ -827,7 +862,7 @@ void UAS::readParametersFromStorage()
void UAS::enableAllDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -853,7 +888,7 @@ void UAS::enableAllDataTransmission(bool enabled)
void UAS::enableRawSensorDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -877,7 +912,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -901,7 +936,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
void UAS::enableRCChannelDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -920,12 +955,16 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
#elif defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
mavlink_message_t msg;
mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
sendMessage(msg);
#endif
}
void UAS::enableRawControllerDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -949,7 +988,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
void UAS::enableRawSensorFusionTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -973,7 +1012,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
void UAS::enablePositionTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -997,7 +1036,7 @@ void UAS::enablePositionTransmission(bool enabled)
void UAS::enableExtra1Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1021,7 +1060,7 @@ void UAS::enableExtra1Transmission(bool enabled)
void UAS::enableExtra2Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1045,7 +1084,7 @@ void UAS::enableExtra2Transmission(bool enabled)
void UAS::enableExtra3Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1161,7 +1200,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
// if(mode == (int)MAV_MODE_MANUAL)
// {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message);
......@@ -1191,7 +1230,7 @@ void UAS::receiveButton(int buttonIndex)
break;
}
qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
// qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
}
......
......@@ -36,10 +36,12 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QAction>
#include <QColor>
#include <QPointer>
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "UASWaypointManager.h"
#include "RadioCalibration/RadioCalibrationData.h"
/**
* @brief Interface for all robots.
......@@ -354,6 +356,8 @@ signals:
void remoteControlChannelChanged(int channelId, float raw, float normalized);
/** @brief Remote control RSSI changed */
void remoteControlRSSIChanged(float rssi);
/** @brief Radio Calibration Data has been received from the MAV*/
void radioCalibrationReceived(const QPointer<RadioCalibrationData>&);
/**
* @brief Localization quality changed
......
......@@ -25,6 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @brief Implementation of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
* @author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
#include <QGridLayout>
......@@ -70,6 +71,14 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
layout->addItem(rssiLayout, 2, 0, 1, 2);
setVisible(false);
calibrate = new QPushButton(tr("Calibrate"), this);
QHBoxLayout *calibrateButtonLayout = new QHBoxLayout();
calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter);
layout->addItem(calibrateButtonLayout, 3, 0, 1, 2);
calibrationWindow = new RadioCalibrationWindow(this);
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
}
......@@ -89,6 +98,8 @@ void QGCRemoteControlView::setUASId(int id)
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
}
}
......@@ -98,7 +109,10 @@ void QGCRemoteControlView::setUASId(int id)
{
// New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
}
}
......@@ -173,7 +187,7 @@ void QGCRemoteControlView::changeEvent(QEvent *e)
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
//ui->retranslateUi(this);
break;
default:
break;
......
......@@ -32,6 +32,9 @@ This file is part of the QGROUNDCONTROL project
#include <QWidget>
#include <QVector>
#include <QPushButton>
#include "RadioCalibration/RadioCalibrationWindow.h"
namespace Ui {
class QGCRemoteControlView;
......@@ -68,6 +71,8 @@ protected:
QVector<QProgressBar*> progressBars;
QProgressBar* rssiBar;
QLabel* nameLabel;
QPushButton *calibrate;
RadioCalibrationWindow *calibrationWindow;
private:
Ui::QGCRemoteControlView *ui;
......
#include "AbstractCalibrator.h"
AbstractCalibrator::AbstractCalibrator(QWidget *parent) :
QWidget(parent),
pulseWidth(new QLabel()),
log(new QVector<float>())
{
}
AbstractCalibrator::~AbstractCalibrator()
{
delete log;
}
float AbstractCalibrator::logAverage()
{
float total = 0;
for (int i=0; i<log->size(); ++i)
total += log->value(i);
return floor(total/log->size());
}
float AbstractCalibrator::logExtrema()
{
float extrema = logAverage();
if (logAverage() < 1500)
{
for (int i=0; i<log->size(); ++i)
{
if (log->value(i) < extrema)
extrema = log->value(i);
}
extrema -= 5; // add 5us to prevent integer overflow
}
else
{
for (int i=0; i<log->size(); ++i)
{
if (log->value(i) > extrema)
extrema = log->value(i);
}
extrema += 5; // subtact 5us to prevent integer overflow
}
return extrema;
}
void AbstractCalibrator::channelChanged(float raw)
{
pulseWidth->setText(QString::number(static_cast<double>(raw)));
if (log->size() == 5)
log->pop_front();
log->push_back(raw);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Common aspects of radio calibration widgets
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef ABSTRACTCALIBRATOR_H
#define ABSTRACTCALIBRATOR_H
#include <QWidget>
#include <QString>
#include <QLabel>
#include <QVector>
#include <math.h>
/**
@brief Holds the code which is common to all the radio calibration widgets.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class AbstractCalibrator : public QWidget
{
Q_OBJECT
public:
explicit AbstractCalibrator(QWidget *parent = 0);
~AbstractCalibrator();
/** Change the setpoints of the widget. Used when
changing the display from an external source (file/uav).
@param data QVector of setpoints
*/
virtual void set(const QVector<float>& data)=0;
signals:
/** Announce a setpoint change.
@param index setpoint number - 0 based in the current implementation
@param value new value
*/
void setpointChanged(int index, float value);
public slots:
/** Slot to call when the relevant channel is updated
@param raw current channel value
*/
void channelChanged(float raw);
protected:
/** Display the current pulse width */
QLabel *pulseWidth;
/** Log of the past few samples for use in averaging and finding extrema */
QVector<float> *log;
/** Find the maximum or minimum of the data log */
float logExtrema();
/** Find the average of the log */
float logAverage();
};
#endif // ABSTRACTCALIBRATOR_H
#include "AirfoilServoCalibrator.h"
AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent) :
AbstractCalibrator(parent),
highPulseWidth(new QLabel()),
centerPulseWidth(new QLabel()),
lowPulseWidth(new QLabel())
{
QGridLayout *grid = new QGridLayout(this);
/* Add title */
QHBoxLayout *titleLayout = new QHBoxLayout();
QLabel *title;
if (type == AILERON)
{
title = new QLabel(tr("Aileron"));
}
else if (type == ELEVATOR)
{
title = new QLabel(tr("Elevator"));
}
else if (type == RUDDER)
{
title = new QLabel(tr("Rudder"));
}
titleLayout->addWidget(title);
grid->addLayout(titleLayout, 0, 0, 1, 3, Qt::AlignHCenter);
/* Add current Pulse Width Display */
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 3);
QLabel *highPulseString;
QLabel *centerPulseString;
QLabel *lowPulseString;
if (type == AILERON)
{
highPulseString = new QLabel(tr("Bank Left"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Bank Right"));
}
else if (type == ELEVATOR)
{
highPulseString = new QLabel(tr("Nose Down"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Nose Up"));
}
else if (type == RUDDER)
{
highPulseString = new QLabel(tr("Nose Left"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Nose Right"));
}
else
{
highPulseString = new QLabel(tr("High"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Low"));
}
QPushButton *highButton = new QPushButton(tr("Set"));
QPushButton *centerButton = new QPushButton(tr("Set"));
QPushButton *lowButton = new QPushButton(tr("Set"));
grid->addWidget(highPulseString, 2, 0);
grid->addWidget(highPulseWidth, 2, 1);
grid->addWidget(highButton, 2, 2);
grid->addWidget(centerPulseString, 3, 0);
grid->addWidget(centerPulseWidth, 3, 1);
grid->addWidget(centerButton, 3, 2);
grid->addWidget(lowPulseString, 4, 0);
grid->addWidget(lowPulseWidth, 4, 1);
grid->addWidget(lowButton, 4, 2);
this->setLayout(grid);
connect(highButton, SIGNAL(clicked()), this, SLOT(setHigh()));
connect(centerButton, SIGNAL(clicked()), this, SLOT(setCenter()));
connect(lowButton, SIGNAL(clicked()), this, SLOT(setLow()));
}
void AirfoilServoCalibrator::setHigh()
{
highPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(2, logExtrema());
}
void AirfoilServoCalibrator::setCenter()
{
centerPulseWidth->setText(QString::number(static_cast<double>(logAverage())));
emit setpointChanged(1, logAverage());
}
void AirfoilServoCalibrator::setLow()
{
lowPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(0, logExtrema());
}
void AirfoilServoCalibrator::set(const QVector<float> &data)
{
if (data.size() == 3)
{
lowPulseWidth->setText(QString::number(data[0]));
centerPulseWidth->setText(QString::number(data[1]));
highPulseWidth->setText(QString::number(data[2]));
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Calibration widget for 3 point airfoil servo
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef AIRFOILSERVOCALIBRATOR_H
#define AIRFOILSERVOCALIBRATOR_H
#include <QWidget>
#include <QLabel>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget three setpoint control input.
For the helicopter autopilot at UAlberta this is used for Aileron, Elevator, and Rudder channels.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class AirfoilServoCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
enum AirfoilType
{
AILERON,
ELEVATOR,
RUDDER
};
explicit AirfoilServoCalibrator(AirfoilType type = AILERON, QWidget *parent = 0);
/** @param data must have exaclty 3 elemets. they are assumed to be low center high */
void set(const QVector<float>& data);
protected slots:
void setHigh();
void setCenter();
void setLow();
protected:
QLabel *highPulseWidth;
QLabel *centerPulseWidth;
QLabel *lowPulseWidth;
};
#endif // AIRFOILSERVOCALIBRATOR_H
#include "CurveCalibrator.h"
CurveCalibrator::CurveCalibrator(QString titleString, QWidget *parent) :
AbstractCalibrator(parent),
setpoints(new QVector<double>(5)),
positions(new QVector<double>())
{
QGridLayout *grid = new QGridLayout(this);
QLabel *title = new QLabel(titleString);
grid->addWidget(title, 0, 0, 1, 5, Qt::AlignHCenter);
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
pulseWidth = new QLabel();
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 5, Qt::AlignHCenter);
for (int i=0; i<=100; i=i+100/4)
positions->append(static_cast<double>(i));
setpoints->fill(1500);
plot = new QwtPlot();
grid->addWidget(plot, 2, 0, 1, 5, Qt::AlignHCenter);
plot->setAxisScale(QwtPlot::yLeft, 1000, 2000, 200);
plot->setAxisScale(QwtPlot::xBottom, 0, 100, 25);
curve = new QwtPlotCurve();
curve->setPen(QPen(QColor(QString("lime"))));
curve->setData(*positions, *setpoints);
curve->attach(plot);
plot->replot();
QPushButton *zero = new QPushButton(tr("0 %"));
QPushButton *twentyfive = new QPushButton(tr("25 %"));
QPushButton *fifty = new QPushButton(tr("50 %"));
QPushButton *seventyfive = new QPushButton(tr("75 %"));
QPushButton *hundred = new QPushButton(tr("100 %"));
grid->addWidget(zero, 3, 0);
grid->addWidget(twentyfive, 3, 1);
grid->addWidget(fifty, 3, 2);
grid->addWidget(seventyfive, 3, 3);
grid->addWidget(hundred, 3, 4);
this->setLayout(grid);
signalMapper = new QSignalMapper(this);
signalMapper->setMapping(zero, 0);
signalMapper->setMapping(twentyfive, 1);
signalMapper->setMapping(fifty, 2);
signalMapper->setMapping(seventyfive, 3);
signalMapper->setMapping(hundred, 4);
connect(zero, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(twentyfive, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(fifty, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(seventyfive, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(hundred, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(signalMapper, SIGNAL(mapped(int)), this, SLOT(setSetpoint(int)));
}
CurveCalibrator::~CurveCalibrator()
{
delete setpoints;
delete positions;
}
void CurveCalibrator::setSetpoint(int setpoint)
{
if (setpoint == 0 || setpoint == 4)
{
setpoints->replace(setpoint, static_cast<double>(logExtrema()));
}
else
{
setpoints->replace(setpoint, static_cast<double>(logAverage()));
}
curve->setData(*positions, *setpoints);
plot->replot();
emit setpointChanged(setpoint, static_cast<float>(setpoints->value(setpoint)));
}
void CurveCalibrator::set(const QVector<float> &data)
{
if (data.size() == 5)
{
for (int i=0; i<data.size(); ++i)
setpoints->replace(i, static_cast<double>(data[i]));
curve->setData(*positions, *setpoints);
plot->replot();
}
else
{
qDebug() << __FILE__ << __LINE__ << ": wrong data vector size";
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Calibration widget for 5 point inerpolated curve
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef CURVECALIBRATOR_H
#define CURVECALIBRATOR_H
#include <QWidget>
#include <QVector>
#include <qwt_plot.h>
#include <qwt_plot_curve.h>
//#include <qwt_array.h>
#include <QGridLayout>
#include <QHBoxLayout>
#include <QLabel>
#include <QPushButton>
#include <QPen>
#include <QColor>
#include <QString>
#include <QSignalMapper>
#include <QDebug>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget for 5 point inerpolated curve.
For the helicopter autopilot at UAlberta this is used for the throttle and pitch curves.
*/
class CurveCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
explicit CurveCalibrator(QString title = QString(), QWidget *parent = 0);
~CurveCalibrator();
void set(const QVector<float> &data);
protected slots:
void setSetpoint(int setpoint);
protected:
QVector<double> *setpoints;
QVector<double> *positions;
/** Plot to display calibration curve */
QwtPlot *plot;
/** Curve object of calibration curve */
QwtPlotCurve *curve;
QSignalMapper *signalMapper;
};
#endif // CURVECALIBRATOR_H
#include "RadioCalibrationData.h"
RadioCalibrationData::RadioCalibrationData()
{
data = new QVector<QVector<float> >(6);
(*data).insert(AILERON, QVector<float>(3));
(*data).insert(ELEVATOR, QVector<float>(3));
(*data).insert(RUDDER, QVector<float>(3));
(*data).insert(GYRO, QVector<float>(2));
(*data).insert(PITCH, QVector<float>(5));
(*data).insert(THROTTLE, QVector<float>(5));
}
RadioCalibrationData::RadioCalibrationData(const QVector<float> &aileron,
const QVector<float> &elevator,
const QVector<float> &rudder,
const QVector<float> &gyro,
const QVector<float> &pitch,
const QVector<float> &throttle)
{
data = new QVector<QVector<float> >();
(*data) << aileron
<< elevator
<< rudder
<< gyro
<< pitch
<< throttle;
}
RadioCalibrationData::RadioCalibrationData(const RadioCalibrationData &other)
:QObject()
{
data = new QVector<QVector<float> >(*other.data);
}
RadioCalibrationData::~RadioCalibrationData()
{
delete data;
}
const float* RadioCalibrationData::operator [](int i) const
{
if (i < data->size())
{
return (*data)[i].constData();
}
return NULL;
}
const QVector<float>& RadioCalibrationData::operator ()(int i) const
{
if (i < data->size())
{
return (*data)[i];
}
// This is not good. If it is ever used after being returned it will cause a crash
// return QVector<float>();
}
QString RadioCalibrationData::toString(RadioElement element) const
{
QString s;
foreach (float f, (*data)[element])
{
s += QString::number(f) + ", ";
}
return s.mid(0, s.length()-2);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Class to hold the calibration data
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef RADIOCALIBRATIONDATA_H
#define RADIOCALIBRATIONDATA_H
#include <QObject>
#include <QDebug>
#include <QVector>
#include <QString>
/**
@brief Class to hold the calibration data.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class RadioCalibrationData : public QObject
{
Q_OBJECT
public:
explicit RadioCalibrationData();
RadioCalibrationData(const RadioCalibrationData&);
RadioCalibrationData(const QVector<float>& aileron,
const QVector<float>& elevator,
const QVector<float>& rudder,
const QVector<float>& gyro,
const QVector<float>& pitch,
const QVector<float>& throttle);
~RadioCalibrationData();
enum RadioElement
{
AILERON=0,
ELEVATOR,
RUDDER,
GYRO,
PITCH,
THROTTLE
};
const float* operator[](int i) const;
const QVector<float>& operator()(int i) const;
void set(int element, int index, float value) {(*data)[element][index] = value;}
public slots:
void setAileron(int index, float value) {set(AILERON, index, value);}
void setElevator(int index, float value) {set(ELEVATOR, index, value);}
void setRudder(int index, float value) {set(RUDDER, index, value);}
void setGyro(int index, float value) {set(GYRO, index, value);}
void setPitch(int index, float value) {set(PITCH, index, value);}
void setThrottle(int index, float value) {set(THROTTLE, index, value);}
public:
/// Creates a comma seperated list of the values for a particular element
QString toString(const RadioElement element) const;
protected:
QVector<QVector<float> > *data;
void init(const QVector<float>& aileron,
const QVector<float>& elevator,
const QVector<float>& rudder,
const QVector<float>& gyro,
const QVector<float>& pitch,
const QVector<float>& throttle);
};
#endif // RADIOCALIBRATIONDATA_H
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Main window for radio calibration
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef RADIOCALIBRATIONWINDOW_H
#define RADIOCALIBRATIONWINDOW_H
#include <QWidget>
#include <QLabel>
#include <QGroupBox>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include <QDebug>
#include <QPointer>
#include <QFileDialog>
#include <QFile>
#include <QtXml>
#include <QTextStream>
#include "AirfoilServoCalibrator.h"
#include "SwitchCalibrator.h"
#include "CurveCalibrator.h"
#include "mavlink.h"
#include "mavlink_types.h"
#include "UAS.h"
#include "UASManager.h"
#include "RadioCalibrationData.h"
/**
@brief Main window for radio calibration
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class RadioCalibrationWindow : public QWidget
{
Q_OBJECT
public:
explicit RadioCalibrationWindow(QWidget *parent = 0);
public slots:
void setChannel(int ch, float raw, float normalized);
void loadFile();
void saveFile();
void send();
void request();
void receive(const QPointer<RadioCalibrationData>& radio);
void setUASId(int id) {this->uasId = id;}
protected:
AirfoilServoCalibrator *aileron;
AirfoilServoCalibrator *elevator;
AirfoilServoCalibrator *rudder;
SwitchCalibrator *gyro;
CurveCalibrator *pitch;
CurveCalibrator *throttle;
int uasId;
QPointer<RadioCalibrationData> radio;
QSignalMapper mapper;
void parseSetpoint(const QDomElement& setpoint, const QPointer<RadioCalibrationData>& radio);
};
#endif // RADIOCALIBRATIONWINDOW_H
#include "SwitchCalibrator.h"
SwitchCalibrator::SwitchCalibrator(QString titleString, QWidget *parent) :
AbstractCalibrator(parent),
defaultPulseWidth(new QLabel()),
toggledPulseWidth(new QLabel())
{
/* Add title label*/
QLabel *title = new QLabel(titleString);
QGridLayout *grid = new QGridLayout();
grid->addWidget(title, 0, 0, 1, 3);
/* Add current Pulse Width Display */
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 3);
QLabel *defaultPulseString = new QLabel(tr("Default Position"));
QPushButton *defaultButton = new QPushButton(tr("Set"));
grid->addWidget(defaultPulseString, 2, 0);
grid->addWidget(defaultPulseWidth, 2, 1);
grid->addWidget(defaultButton, 2, 2);
QLabel *toggledPulseString = new QLabel(tr("Toggled Position"));
QPushButton *toggledButton = new QPushButton(tr("Set"));
grid->addWidget(toggledPulseString, 3, 0);
grid->addWidget(toggledPulseWidth, 3, 1);
grid->addWidget(toggledButton, 3, 2);
this->setLayout(grid);
connect(defaultButton, SIGNAL(clicked()), this, SLOT(setDefault()));
connect(toggledButton, SIGNAL(clicked()), this, SLOT(setToggled()));
}
void SwitchCalibrator::setDefault()
{
defaultPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(0, logExtrema());
}
void SwitchCalibrator::setToggled()
{
toggledPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(1, logExtrema());
}
void SwitchCalibrator::set(const QVector<float> &data)
{
if (data.size() == 2)
{
defaultPulseWidth->setText(QString::number(data[0]));
toggledPulseWidth->setText(QString::number(data[1]));
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Calibration widget for 2 setpoint switch
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef SWITCHCALIBRATOR_H
#define SWITCHCALIBRATOR_H
#include <QWidget>
#include <QLabel>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget for 2 setpoint switch
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class SwitchCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
explicit SwitchCalibrator(QString title=QString(), QWidget *parent = 0);
void set(const QVector<float> &data);
protected slots:
void setDefault();
void setToggled();
protected:
QLabel *defaultPulseWidth;
QLabel *toggledPulseWidth;
};
#endif // SWITCHCALIBRATOR_H
......@@ -23,22 +23,10 @@
#
#-------------------------------------------------
# Uncomment ONE of these lines to enable the special message set of a project.
# Several message sets can be also enabled in parallel, as long as function names
# and message ids do not conflict.
# Add or remove custom message specs here. The matching mavlink headers are
# included in the main qgroundcontrol.pro file.
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
MAVLINK_CONF += pixhawk \
slugs \
ualberta
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