Commit 79b910ab authored by Lorenz Meier's avatar Lorenz Meier

Enable RC calibration mode during RC calibration to tell vehicle to ignore...

Enable RC calibration mode during RC calibration to tell vehicle to ignore stick inputs for that period
parent c283bbea
......@@ -1661,7 +1661,15 @@ void UAS::startRadioControlCalibration()
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
sendMessage(msg);
}
void UAS::endRadioControlCalibration()
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(msg);
}
......
......@@ -912,6 +912,7 @@ public slots:
void setLocalPositionOffset(float x, float y, float z, float yaw);
void startRadioControlCalibration();
void endRadioControlCalibration();
void startMagnetometerCalibration();
void startGyroscopeCalibration();
void startPressureCalibration();
......
......@@ -371,6 +371,7 @@ public slots:
virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0;
virtual void startRadioControlCalibration() = 0;
virtual void endRadioControlCalibration() = 0;
virtual void startMagnetometerCalibration() = 0;
virtual void startGyroscopeCalibration() = 0;
virtual void startPressureCalibration() = 0;
......
......@@ -481,6 +481,8 @@ void QGCPX4VehicleConfig::startCalibrationRC()
return;
}
mav->startRadioControlCalibration();
// reset all channel mappings above Ch 5 to invalid/unused value before starting calibration
for (unsigned int j= 5; j < chanMappedMax; j++) {
rcMapping[j] = -1;
......@@ -529,6 +531,8 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
if (!calibrationEnabled)
return;
mav->endRadioControlCalibration();
// Try to identify inverted channels, but only for R/P/Y/T
for (int i = 0; i < 4; i++) {
detectChannelInversion(i);
......
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