mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge branch 'laurent/OP-1723_Allow_RcCar_reverse' into next
This commit is contained in:
commit
0947ab6433
@ -60,10 +60,10 @@ QStringList ConfigGroundVehicleWidget::getChannelDescriptions()
|
||||
channelDesc[configData.ground.GroundVehicleSteering2 - 1] = QString("GroundSteering2");
|
||||
}
|
||||
if (configData.ground.GroundVehicleThrottle1 > 0) {
|
||||
channelDesc[configData.ground.GroundVehicleThrottle1 - 1] = QString("GroundThrottle1");
|
||||
channelDesc[configData.ground.GroundVehicleThrottle1 - 1] = QString("GroundMotor1");
|
||||
}
|
||||
if (configData.ground.GroundVehicleThrottle2 > 0) {
|
||||
channelDesc[configData.ground.GroundVehicleThrottle2 - 1] = QString("GroundThrottle2");
|
||||
channelDesc[configData.ground.GroundVehicleThrottle2 - 1] = QString("GroundMotor2");
|
||||
}
|
||||
return channelDesc;
|
||||
}
|
||||
@ -116,6 +116,13 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setEnabled(true);
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setEnabled(true);
|
||||
|
||||
// Default Curve2 range -1 -> +1, allow forward/reverse (Car and Tank)
|
||||
m_aircraft->groundVehicleThrottle1->setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
|
||||
m_aircraft->groundVehicleThrottle2->setMixerType(MixerCurve::MIXERCURVE_PITCH);
|
||||
|
||||
initMixerCurves(frameType);
|
||||
|
||||
|
||||
if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)") {
|
||||
// Tank
|
||||
m_vehicleImg->setElementId("tank");
|
||||
@ -159,9 +166,9 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
|
||||
// Motorcycle
|
||||
m_vehicleImg->setElementId("motorbike");
|
||||
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle"));
|
||||
m_aircraft->gvMotor1ChannelBox->setEnabled(false);
|
||||
m_aircraft->gvMotor2ChannelBox->setEnabled(true);
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setEnabled(false);
|
||||
|
||||
m_aircraft->gvMotor1ChannelBox->setEnabled(true);
|
||||
m_aircraft->gvMotor2ChannelBox->setEnabled(false);
|
||||
|
||||
m_aircraft->gvMotor2Label->setText("Rear motor");
|
||||
|
||||
@ -171,7 +178,11 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
|
||||
m_aircraft->gvSteering1Label->setText("Front steering");
|
||||
m_aircraft->gvSteering2Label->setText("Balancing");
|
||||
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
|
||||
// Curve1 for Motorcyle
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Rear throttle curve");
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setEnabled(true);
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setTitle("");
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setEnabled(false);
|
||||
|
||||
// Curve range 0 -> +1 (no reverse)
|
||||
m_aircraft->groundVehicleThrottle2->setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
|
||||
@ -201,19 +212,24 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType)
|
||||
m_aircraft->gvSteering1Label->setText("Front steering");
|
||||
m_aircraft->gvSteering2Label->setText("Rear steering");
|
||||
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve");
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
|
||||
// Curve2 for Car
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Throttle curve");
|
||||
m_aircraft->gvThrottleCurve2GroupBox->setEnabled(true);
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setTitle("");
|
||||
m_aircraft->gvThrottleCurve1GroupBox->setEnabled(false);
|
||||
|
||||
m_aircraft->groundVehicleThrottle2->setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
|
||||
m_aircraft->groundVehicleThrottle2->setMixerType(MixerCurve::MIXERCURVE_PITCH);
|
||||
m_aircraft->groundVehicleThrottle1->setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
|
||||
|
||||
initMixerCurves(frameType);
|
||||
|
||||
// If new setup, set curves values
|
||||
if (frameTypeSaved->getValue().toString() != "GroundVehicleCar") {
|
||||
// Curve range 0 -> +1 (no reverse)
|
||||
m_aircraft->groundVehicleThrottle1->initLinearCurve(5, 1.0);
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(5, 1.0);
|
||||
// Set curve2 range from -0.926 to 1 (forward / reverse)
|
||||
// Take in account 4% offset in Throttle input after calibration
|
||||
// 0.5 / 0.54 = 0.926
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(5, 1.0, -0.926);
|
||||
}
|
||||
}
|
||||
|
||||
@ -321,6 +337,8 @@ void ConfigGroundVehicleWidget::initMixerCurves(QString frameType)
|
||||
// no, init a straight curve
|
||||
if (frameType == "GroundVehicleDifferential") {
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(curveValues.count(), 0.8, -0.8);
|
||||
} else if (frameType == "GroundVehicleCar") {
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(curveValues.count(), 1.0, -1.0);
|
||||
} else {
|
||||
m_aircraft->groundVehicleThrottle2->initLinearCurve(curveValues.count(), 1.0);
|
||||
}
|
||||
@ -388,7 +406,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeTyp
|
||||
|
||||
// motor
|
||||
int channel = m_aircraft->gvMotor2ChannelBox->currentIndex() - 1;
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_REVERSABLEMOTOR);
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
|
||||
|
||||
@ -495,7 +513,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
|
||||
|
||||
channel = m_aircraft->gvMotor1ChannelBox->currentIndex() - 1;
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_REVERSABLEMOTOR);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
|
||||
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 127);
|
||||
|
||||
channel = m_aircraft->gvMotor2ChannelBox->currentIndex() - 1;
|
||||
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_REVERSABLEMOTOR);
|
||||
|
@ -104,6 +104,16 @@ void EscCalibrationPage::startButtonClicked()
|
||||
QString mixerTypePattern = "Mixer%1Type";
|
||||
|
||||
OutputCalibrationUtil::startOutputCalibration();
|
||||
// First check if any servo and set his value to 1500 (like Tricopter)
|
||||
for (quint32 i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
|
||||
UAVObjectField *field = mSettings->getField(mixerTypePattern.arg(i + 1));
|
||||
Q_ASSERT(field);
|
||||
if (field->getValue().toString() == field->getOptions().at(VehicleConfigurationHelper::MIXER_TYPE_SERVO)) {
|
||||
m_outputUtil.startChannelOutput(i, 1500);
|
||||
m_outputUtil.stopChannelOutput();
|
||||
}
|
||||
}
|
||||
// Find motors and start Esc procedure
|
||||
for (quint32 i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
|
||||
UAVObjectField *field = mSettings->getField(mixerTypePattern.arg(i + 1));
|
||||
Q_ASSERT(field);
|
||||
|
@ -54,6 +54,8 @@ OutputCalibrationPage::~OutputCalibrationPage()
|
||||
delete m_calibrationUtil;
|
||||
m_calibrationUtil = 0;
|
||||
}
|
||||
|
||||
OutputCalibrationUtil::stopOutputCalibration();
|
||||
delete ui;
|
||||
}
|
||||
|
||||
@ -70,18 +72,32 @@ void OutputCalibrationPage::setupActuatorMinMaxAndNeutral(int motorChannelStart,
|
||||
// servos since a value out of range can actually destroy the
|
||||
// vehicle if unlucky.
|
||||
// Motors are not that important. REMOVE propellers always!!
|
||||
OutputCalibrationUtil::startOutputCalibration();
|
||||
|
||||
for (int servoid = 0; servoid < 12; servoid++) {
|
||||
if (servoid >= motorChannelStart && servoid <= motorChannelEnd) {
|
||||
// Set to motor safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 1900;
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 1900;
|
||||
m_actuatorSettings[servoid].isReversableMotor = false;
|
||||
// Car and Tank should use reversable Esc/motors
|
||||
if ((getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_CAR)
|
||||
|| (getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_DIFFERENTIAL)) {
|
||||
m_actuatorSettings[servoid].channelNeutral = 1500;
|
||||
m_actuatorSettings[servoid].isReversableMotor = true;
|
||||
// Set initial output value
|
||||
m_calibrationUtil->startChannelOutput(servoid, 1500);
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
}
|
||||
} else if (servoid < totalUsedChannels) {
|
||||
// Set to servo safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1500;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1500;
|
||||
m_actuatorSettings[servoid].channelMax = 1500;
|
||||
// Set initial servo output value
|
||||
m_calibrationUtil->startChannelOutput(servoid, 1500);
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
} else {
|
||||
// "Disable" these channels
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
@ -101,6 +117,8 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_currentWizardIndex = 0;
|
||||
m_vehicleScene->clear();
|
||||
|
||||
resetOutputCalibrationUtil();
|
||||
|
||||
switch (getWizard()->getVehicleSubType()) {
|
||||
case SetupWizard::MULTI_ROTOR_TRI_Y:
|
||||
// Loads the SVG file resourse and sets the scene
|
||||
@ -120,7 +138,7 @@ void OutputCalibrationPage::setupVehicle()
|
||||
// The channel number to configure for each step.
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(0, 2, 3);
|
||||
setupActuatorMinMaxAndNeutral(0, 2, 4);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
@ -180,7 +198,7 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
m_channelIndex << 0 << 2 << 0 << 5 << 1 << 3;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 5);
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 6); // should be 5 instead 6 but output 5 is not used
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
@ -213,7 +231,7 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
m_channelIndex << 0 << 2 << 0 << 5 << 3 << 1;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 5);
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 6); // should be 5 instead 6 but output 5 is not used
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
@ -226,7 +244,7 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2;
|
||||
m_channelIndex << 0 << 1 << 0;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(0, 1, 2);
|
||||
setupActuatorMinMaxAndNeutral(1, 1, 2);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
@ -248,7 +266,7 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2;
|
||||
m_channelIndex << 0 << 1 << 0;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(0, 1, 2);
|
||||
setupActuatorMinMaxAndNeutral(1, 1, 2);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
@ -257,12 +275,6 @@ void OutputCalibrationPage::setupVehicle()
|
||||
break;
|
||||
}
|
||||
|
||||
if (m_calibrationUtil) {
|
||||
delete m_calibrationUtil;
|
||||
m_calibrationUtil = 0;
|
||||
}
|
||||
m_calibrationUtil = new OutputCalibrationUtil();
|
||||
|
||||
setupVehicleItems();
|
||||
}
|
||||
|
||||
@ -326,7 +338,15 @@ void OutputCalibrationPage::setWizardPage()
|
||||
if (currentChannel >= 0) {
|
||||
if (currentPageIndex == 1) {
|
||||
ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->motorPWMValue->setText(QString(tr("Output value : <b>%1</b> µs")).arg(m_actuatorSettings[currentChannel].channelNeutral));
|
||||
// Reversable motor found
|
||||
if (m_actuatorSettings[currentChannel].isReversableMotor) {
|
||||
ui->motorNeutralSlider->setMinimum(m_actuatorSettings[currentChannel].channelMin);
|
||||
ui->motorNeutralSlider->setMaximum(m_actuatorSettings[currentChannel].channelMax);
|
||||
ui->motorInfo->setText(tr("<html><head/><body><p><span style=\" font-size:10pt;\">To find </span><span style=\" font-size:10pt; font-weight:600;\">the neutral rate for this reversable motor</span><span style=\" font-size:10pt;\">, press the Start button below and slide the slider to the right or left until you find the value where the motor doesn't start. <br/><br/>When done press button again to stop.</span></p></body></html>"));
|
||||
}
|
||||
} else if (currentPageIndex == 2) {
|
||||
ui->servoPWMValue->setText(tr("Output value : <b>%1</b> µs").arg(m_actuatorSettings[currentChannel].channelNeutral));
|
||||
if (m_actuatorSettings[currentChannel].channelMax < m_actuatorSettings[currentChannel].channelMin &&
|
||||
!ui->reverseCheckbox->isChecked()) {
|
||||
ui->reverseCheckbox->setChecked(true);
|
||||
@ -416,6 +436,11 @@ void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked)
|
||||
ui->motorNeutralSlider->setEnabled(checked);
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelMin;
|
||||
|
||||
if (m_actuatorSettings[channel].isReversableMotor) {
|
||||
safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
}
|
||||
|
||||
onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, safeValue, ui->motorNeutralSlider);
|
||||
}
|
||||
|
||||
@ -425,7 +450,6 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16
|
||||
if (checkAlarms()) {
|
||||
enableButtons(false);
|
||||
enableServoSliders(true);
|
||||
OutputCalibrationUtil::startOutputCalibration();
|
||||
m_calibrationUtil->startChannelOutput(channel, safeValue);
|
||||
slider->setValue(value);
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
@ -433,8 +457,16 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16
|
||||
button->setChecked(false);
|
||||
}
|
||||
} else {
|
||||
// Servos and ReversableMotors
|
||||
m_calibrationUtil->startChannelOutput(channel, m_actuatorSettings[channel].channelNeutral);
|
||||
|
||||
// Normal motor
|
||||
if ((button == ui->motorNeutralButton) && !m_actuatorSettings[channel].isReversableMotor) {
|
||||
m_calibrationUtil->startChannelOutput(channel, m_actuatorSettings[channel].channelMin);
|
||||
}
|
||||
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
OutputCalibrationUtil::stopOutputCalibration();
|
||||
|
||||
enableServoSliders(false);
|
||||
enableButtons(true);
|
||||
}
|
||||
@ -492,6 +524,8 @@ void OutputCalibrationPage::debugLogChannelValues()
|
||||
void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
|
||||
{
|
||||
Q_UNUSED(value);
|
||||
ui->motorPWMValue->setText(tr("Output value : <b>%1</b> µs").arg(value));
|
||||
|
||||
if (ui->motorNeutralButton->isChecked()) {
|
||||
quint16 value = ui->motorNeutralSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
@ -515,6 +549,7 @@ void OutputCalibrationPage::on_servoCenterAngleSlider_valueChanged(int position)
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
quint16 channel = getCurrentChannel();
|
||||
m_actuatorSettings[channel].channelNeutral = value;
|
||||
ui->servoPWMValue->setText(tr("Output value : <b>%1</b> µs").arg(value));
|
||||
|
||||
// Adjust min and max
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
@ -615,3 +650,12 @@ void OutputCalibrationPage::on_reverseCheckbox_toggled(bool checked)
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMax);
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::resetOutputCalibrationUtil()
|
||||
{
|
||||
if (m_calibrationUtil) {
|
||||
delete m_calibrationUtil;
|
||||
m_calibrationUtil = 0;
|
||||
}
|
||||
m_calibrationUtil = new OutputCalibrationUtil();
|
||||
}
|
||||
|
@ -100,6 +100,7 @@ private:
|
||||
QList<actuatorChannelSettings> m_actuatorSettings;
|
||||
|
||||
OutputCalibrationUtil *m_calibrationUtil;
|
||||
void resetOutputCalibrationUtil();
|
||||
|
||||
static const QString MULTI_SVG_FILE;
|
||||
static const QString FIXEDWING_SVG_FILE;
|
||||
|
@ -6,8 +6,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
<width>776</width>
|
||||
<height>505</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
@ -94,8 +94,10 @@ p, li { white-space: pre-wrap; }
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Cantarell'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br />Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </span></p>
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To find </span><span style=" font-size:10pt; font-weight:600;">the neutral rate for this motor</span><span style=" font-size:10pt;">, press the Start button below and slide the slider to the right until the motor just starts to spin stable. <br /><br />When done press button again to stop.</span></p></body></html></string>
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br />Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </span></p></body></html></string>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::RichText</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -105,6 +107,29 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="motorInfo">
|
||||
<property name="text">
|
||||
<string><html><head/><body><p><span style=" font-size:10pt;">To find </span><span style=" font-size:10pt; font-weight:600;">the neutral rate for this motor</span><span style=" font-size:10pt;">, press the Start button below and slide the slider to the right until the motor just starts to spin stable. <br/><br/>When done press button again to stop.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::RichText</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="motorPWMValue">
|
||||
<property name="text">
|
||||
<string>Output value: 1000µs</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="motorNeutralSlider">
|
||||
<property name="enabled">
|
||||
@ -184,6 +209,13 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="servoPWMValue">
|
||||
<property name="text">
|
||||
<string>Output value: 1000µs</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QWidget" name="widget" native="true">
|
||||
<layout class="QFormLayout" name="formLayout">
|
||||
|
@ -679,8 +679,10 @@ void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings ch
|
||||
}
|
||||
}
|
||||
|
||||
// Default maxThrottle
|
||||
// Default maxThrottle and minThrottle
|
||||
float maxThrottle = 0.9;
|
||||
float minThrottle = 0;
|
||||
|
||||
|
||||
// Save mixer values for sliders
|
||||
switch (m_configSource->getVehicleType()) {
|
||||
@ -737,17 +739,26 @@ void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings ch
|
||||
{
|
||||
switch (m_configSource->getVehicleSubType()) {
|
||||
case VehicleConfigurationSource::GROUNDVEHICLE_MOTORCYCLE:
|
||||
case VehicleConfigurationSource::GROUNDVEHICLE_CAR:
|
||||
mSettings->setMixerValueRoll(100);
|
||||
mSettings->setMixerValuePitch(100);
|
||||
mSettings->setMixerValueYaw(100);
|
||||
maxThrottle = 1;
|
||||
break;
|
||||
case VehicleConfigurationSource::GROUNDVEHICLE_CAR:
|
||||
mSettings->setMixerValueRoll(100);
|
||||
mSettings->setMixerValuePitch(100);
|
||||
mSettings->setMixerValueYaw(100);
|
||||
// Set curve2 range from -0.926 to 1 : take in account 4% offset in Throttle input
|
||||
// 0.5 / 0.54 = 0.926
|
||||
maxThrottle = 1;
|
||||
minThrottle = -0.926;
|
||||
break;
|
||||
case VehicleConfigurationSource::GROUNDVEHICLE_DIFFERENTIAL:
|
||||
mSettings->setMixerValueRoll(100);
|
||||
mSettings->setMixerValuePitch(100);
|
||||
mSettings->setMixerValueYaw(100);
|
||||
maxThrottle = 0.8;
|
||||
minThrottle = -0.8;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -765,7 +776,7 @@ void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings ch
|
||||
UAVObjectField *field = mSettings->getField(throttlePattern.arg(i));
|
||||
Q_ASSERT(field);
|
||||
for (quint32 i = 0; i < field->getNumElements(); i++) {
|
||||
field->setValue(i * (maxThrottle / (field->getNumElements() - 1)), i);
|
||||
field->setValue(minThrottle + (i * ((maxThrottle - minThrottle) / (field->getNumElements() - 1))), i);
|
||||
}
|
||||
}
|
||||
|
||||
@ -2033,7 +2044,7 @@ void VehicleConfigurationHelper::setupCar()
|
||||
channels[0].yaw = 100;
|
||||
|
||||
// Motor (Chan 2)
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].type = MIXER_TYPE_REVERSABLEMOTOR;
|
||||
channels[1].throttle1 = 0;
|
||||
channels[1].throttle2 = 100;
|
||||
channels[1].roll = 0;
|
||||
@ -2058,7 +2069,7 @@ void VehicleConfigurationHelper::setupTank()
|
||||
GUIConfigDataUnion guiSettings = getGUIConfigData();
|
||||
|
||||
// Left Motor (Chan 1)
|
||||
channels[0].type = MIXER_TYPE_SERVO;
|
||||
channels[0].type = MIXER_TYPE_REVERSABLEMOTOR;
|
||||
channels[0].throttle1 = 0;
|
||||
channels[0].throttle2 = 100;
|
||||
channels[0].roll = 0;
|
||||
@ -2066,7 +2077,7 @@ void VehicleConfigurationHelper::setupTank()
|
||||
channels[0].yaw = 100;
|
||||
|
||||
// Right Motor (Chan 2)
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].type = MIXER_TYPE_REVERSABLEMOTOR;
|
||||
channels[1].throttle1 = 0;
|
||||
channels[1].throttle2 = 100;
|
||||
channels[1].roll = 0;
|
||||
@ -2098,10 +2109,10 @@ void VehicleConfigurationHelper::setupMotorcycle()
|
||||
channels[0].pitch = 0;
|
||||
channels[0].yaw = 100;
|
||||
|
||||
// Motor (Chan 2)
|
||||
// Motor (Chan 2) : Curve1, no reverse
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 0;
|
||||
channels[1].throttle2 = 100;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = 0;
|
||||
channels[1].pitch = 0;
|
||||
channels[1].yaw = 0;
|
||||
|
@ -46,9 +46,10 @@ struct actuatorChannelSettings {
|
||||
quint16 channelMin;
|
||||
quint16 channelNeutral;
|
||||
quint16 channelMax;
|
||||
bool isReversableMotor;
|
||||
|
||||
// Default values
|
||||
actuatorChannelSettings() : channelMin(1000), channelNeutral(1000), channelMax(1900) {}
|
||||
actuatorChannelSettings() : channelMin(1000), channelNeutral(1000), channelMax(1900), isReversableMotor(false) {}
|
||||
};
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user