Commit 1550501f authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #1785 from mavlink/uavcan_config

UAVCAN config button
parents a4e55db2 bf51f87f
Subproject commit d23a551e108d92c7a49a66d162cb9d542bbe6be1
Subproject commit c390a63abfce15af0629bdf207c4b6a183fed118
......@@ -263,6 +263,37 @@ QGCView {
}
}
QGCLabel {
text: "UAVCAN ESC Configuration"
font.pixelSize: ScreenTools.mediumFontPixelSize
}
Rectangle {
width: parent.width
height: 140
color: palette.windowShade
Column {
anchors.margins: 10
anchors.fill: parent
spacing: 10
QGCLabel {
color: "yellow"
text: "<font color=\"yellow\">WARNING: Propellers must be removed from vehicle prior to performing UAVCAN ESC configuration.</font>"
}
QGCLabel {
text: "You must use USB connection for this operation."
}
QGCButton {
text: "Configure"
onClicked: controller.busConfigureActuators()
}
}
}
/*
* This is disabled for now
Row {
......
......@@ -49,11 +49,23 @@ void PowerComponentController::calibrateEsc(void)
_uas->startCalibration(UASInterface::StartCalibrationEsc);
}
void PowerComponentController::busConfigureActuators(void)
{
_warningMessages.clear();
connect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
_uas->startBusConfig(UASInterface::StartBusConfigActuators);
}
void PowerComponentController::_stopCalibration(void)
{
disconnect(_uas, &UASInterface::textMessageReceived, this, &PowerComponentController::_handleUASTextMessage);
}
void PowerComponentController::_stopBusConfig(void)
{
_stopCalibration();
}
void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
Q_UNUSED(compId);
......@@ -130,8 +142,28 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int
return;
}
QString warningPrefix("calibration warning: ");
QString warningPrefix("config warning: ");
if (text.startsWith(warningPrefix)) {
_warningMessages << text.right(text.length() - warningPrefix.length());
}
QString busFailedPrefix("bus conf fail:");
if (text.startsWith(busFailedPrefix)) {
_stopBusConfig();
emit calibrationFailed(text.right(text.length() - failedPrefix.length()));
return;
}
QString busCompletePrefix("bus conf done:");
if (text.startsWith(calCompletePrefix)) {
_stopBusConfig();
emit calibrationSuccess(_warningMessages);
return;
}
QString busWarningPrefix("bus conf warn: ");
if (text.startsWith(busWarningPrefix)) {
_warningMessages << text.right(text.length() - warningPrefix.length());
}
}
......@@ -43,6 +43,7 @@ public:
~PowerComponentController();
Q_INVOKABLE void calibrateEsc(void);
Q_INVOKABLE void busConfigureActuators(void);
signals:
void oldFirmware(void);
......@@ -59,6 +60,7 @@ private slots:
private:
void _stopCalibration(void);
void _stopBusConfig(void);
QStringList _warningMessages;
static const int _neededFirmwareRev = 1;
......
......@@ -1515,6 +1515,9 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
case StartCalibrationEsc:
escCal = 1;
break;
case StartCalibrationUavcanEsc:
escCal = 2;
break;
}
mavlink_message_t msg;
......@@ -1555,6 +1558,54 @@ void UAS::stopCalibration(void)
sendMessage(msg);
}
void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
{
int actuatorCal = 0;
switch (calType) {
case StartBusConfigActuators:
actuatorCal = 1;
break;
}
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
actuatorCal, // actuators
0,
0,
0,
0,
0,
0);
sendMessage(msg);
}
void UAS::stopBusConfig(void)
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&msg,
uasId,
0, // target component
MAV_CMD_PREFLIGHT_UAVCAN, // command id
0, // 0=first transmission of command
0,
0,
0,
0,
0,
0,
0);
sendMessage(msg);
}
void UAS::startDataRecording()
{
mavlink_message_t msg;
......
......@@ -916,6 +916,9 @@ public slots:
void startCalibration(StartCalibrationType calType);
void stopCalibration(void);
void startBusConfig(StartBusConfigType calType);
void stopBusConfig(void);
void startDataRecording();
void stopDataRecording();
void deleteSettings();
......
......@@ -249,7 +249,12 @@ public:
StartCalibrationAccel,
StartCalibrationLevel,
StartCalibrationEsc,
StartCalibrationCopyTrims
StartCalibrationCopyTrims,
StartCalibrationUavcanEsc
};
enum StartBusConfigType {
StartBusConfigActuators
};
/// Starts the specified calibration
......@@ -258,6 +263,12 @@ public:
/// Ends any current calibration
virtual void stopCalibration(void) = 0;
/// Starts the specified bus configuration
virtual void startBusConfig(StartBusConfigType calType) = 0;
/// Ends any current bus configuration
virtual void stopBusConfig(void) = 0;
public slots:
/** @brief Set a new name for the system */
......
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