mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-29 14:52:12 +01:00
OP-1063 Multi_config_Hexa_fixes Added OctoX, define new mixer table for Octo(p) and OctoX. New motor definition for OctoX (NNE, ENE...) Fixes for svg frames. Defined default settings for OctoP/X in setupwizard (but disabled)
This commit is contained in:
parent
5b3f2513c6
commit
c26e33964a
@ -265,6 +265,7 @@ FrameType_t GetCurrentFrameType()
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAH:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV:
|
||||
|
@ -190,7 +190,8 @@ static void vtolPathFollowerTask(__attribute__((unused)) void *parameters)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXA) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTO)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP)
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_TRI) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXAH)) {
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_TRI) && (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_HEXAH))
|
||||
&& (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_WARNING);
|
||||
vTaskDelay(1000);
|
||||
continue;
|
||||
|
@ -55,6 +55,32 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
|
||||
// get the gui config data
|
||||
GUIConfigDataUnion configData = getConfigData();
|
||||
multiGUISettingsStruct multi = configData.multi;
|
||||
/* Octocopter X motor definition */
|
||||
if (multi.VTOLMotorNNE > 0 && multi.VTOLMotorNNE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorNNE - 1] = QString("VTOLMotorNNE");
|
||||
}
|
||||
if (multi.VTOLMotorENE > 0 && multi.VTOLMotorENE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorENE - 1] = QString("VTOLMotorENE");
|
||||
}
|
||||
if (multi.VTOLMotorESE > 0 && multi.VTOLMotorESE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorESE - 1] = QString("VTOLMotorESE");
|
||||
}
|
||||
if (multi.VTOLMotorSSE > 0 && multi.VTOLMotorSSE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorSSE - 1] = QString("VTOLMotorSSE");
|
||||
}
|
||||
if (multi.VTOLMotorSSW > 0 && multi.VTOLMotorSSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorSSW - 1] = QString("VTOLMotorSSW");
|
||||
}
|
||||
if (multi.VTOLMotorWSW > 0 && multi.VTOLMotorWSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorWSW - 1] = QString("VTOLMotorWSW");
|
||||
}
|
||||
if (multi.VTOLMotorWNW > 0 && multi.VTOLMotorWNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorWNW - 1] = QString("VTOLMotorWNW");
|
||||
}
|
||||
if (multi.VTOLMotorNNW > 0 && multi.VTOLMotorNNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorNNW - 1] = QString("VTOLMotorNNW");
|
||||
}
|
||||
// End OctocopterX
|
||||
|
||||
if (multi.VTOLMotorN > 0 && multi.VTOLMotorN <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) {
|
||||
channelDesc[multi.VTOLMotorN - 1] = QString("VTOLMotorN");
|
||||
@ -111,7 +137,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
|
||||
|
||||
QStringList multiRotorTypes;
|
||||
multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Hexacopter" << "Hexacopter X" << "Hexacopter H" << "Hexacopter Y6"
|
||||
<< "Octocopter" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
<< "Octocopter" << "Octocopter X" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
|
||||
|
||||
// Set default model to "Quad X"
|
||||
@ -185,9 +211,15 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(33);
|
||||
m_aircraft->mrPitchMixLevel->setValue(33);
|
||||
setYawMixLevel(25);
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100%
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter X"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix
|
||||
m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100%
|
||||
setYawMixLevel(100);
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType,
|
||||
m_aircraft->multirotorFrameType->findText("Octocopter V"));
|
||||
@ -248,6 +280,8 @@ void ConfigMultiRotorWidget::setupEnabledControls(QString frameType)
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 8, true);
|
||||
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
|
||||
@ -288,6 +322,14 @@ void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData)
|
||||
configData->multi.VTOLMotorW = 0;
|
||||
configData->multi.VTOLMotorNW = 0;
|
||||
configData->multi.TRIYaw = 0;
|
||||
configData->multi.VTOLMotorNNE = 0;
|
||||
configData->multi.VTOLMotorENE = 0;
|
||||
configData->multi.VTOLMotorESE = 0;
|
||||
configData->multi.VTOLMotorSSE = 0;
|
||||
configData->multi.VTOLMotorSSW = 0;
|
||||
configData->multi.VTOLMotorWSW = 0;
|
||||
configData->multi.VTOLMotorWNW = 0;
|
||||
configData->multi.VTOLMotorNNW = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -380,7 +422,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
//get motor 2 value for Yaw and Roll
|
||||
channel += 1;
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
@ -409,7 +451,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
//get motor 2 value for Yaw and Roll
|
||||
channel += 1;
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
@ -492,11 +534,11 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
// change channels
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
// Get M3 Roll value
|
||||
channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
} else if (frameType == "OctoV") {
|
||||
} else if (frameType == "OctoV") {
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
@ -520,6 +562,34 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
}
|
||||
} else if (frameType == "OctoX") {
|
||||
// Motors 1 to 8 are NNE / ENE / ESE / etc
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNNE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorENE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorESE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSSE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorSSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorWSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox7, multi.VTOLMotorWNW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox8, multi.VTOLMotorNNW);
|
||||
|
||||
|
||||
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
|
||||
// This assumes that all vectors are identical - if not, the user should use the
|
||||
// "custom" setting.
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(-qRound(value / 1.27));
|
||||
|
||||
// Get M2 Roll value
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
} else if (frameType == "OctoCoaxX") {
|
||||
// Motors 1 to 8 are N / NE / E / etc
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW);
|
||||
@ -657,16 +727,40 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
<< "VTOLMotorW" << "VTOLMotorNW";
|
||||
setupMotors(motorList);
|
||||
// Motor 1 to 8:
|
||||
// pitch roll yaw
|
||||
// pitch roll yaw (OctoP)
|
||||
double mixerMatrix[8][3] = {
|
||||
{ 1, 0, -1 },
|
||||
{ 1, -1, 1 },
|
||||
{ 0, -1, -1 },
|
||||
{ -1, -1, 1 },
|
||||
{ -1, 0, -1 },
|
||||
{ -1, 1, 1 },
|
||||
{ 0, 1, -1 },
|
||||
{ 1, 1, 1 }
|
||||
{ 1 , 0 , -1 },
|
||||
{ 0.71,-0.71, 1 },
|
||||
{ 0 ,-1 , -1 },
|
||||
{ -0.71,-0.71, 1 },
|
||||
{ -1 , 0 , -1 },
|
||||
{ -0.71, 0.71, 1 },
|
||||
{ 0 , 1 , -1 },
|
||||
{ 0.71, 0.71, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter X") {
|
||||
airframeType = "OctoX";
|
||||
|
||||
// Show any config errors in GUI
|
||||
if (throwConfigError(8)) {
|
||||
return airframeType;
|
||||
}
|
||||
motorList << "VTOLMotorNNE" << "VTOLMotorENE" << "VTOLMotorESE" << "VTOLMotorSSE" << "VTOLMotorSSW" << "VTOLMotorWSW"
|
||||
<< "VTOLMotorWNW" << "VTOLMotorNNW";
|
||||
setupMotors(motorList);
|
||||
// Motor 1 to 8:
|
||||
// pitch roll yaw (OctoX)
|
||||
double mixerMatrix[8][3] = {
|
||||
{ 1 ,-0.41, -1 },
|
||||
{ 0.41, -1 , 1 },
|
||||
{ -0.41, -1 , -1 },
|
||||
{ -1 ,-0.41, 1 },
|
||||
{ -1 , 0.41, -1 },
|
||||
{ -0.41, 1 , 1 },
|
||||
{ 0.41, 1 , -1 },
|
||||
{ 1 , 0.41, 1 }
|
||||
};
|
||||
setupMultiRotorMixer(mixerMatrix);
|
||||
m_aircraft->mrStatusLabel->setText("Configuration OK");
|
||||
@ -828,6 +922,8 @@ void ConfigMultiRotorWidget::updateAirframe(QString frameType)
|
||||
elementId = "hexa-coax";
|
||||
} else if (frameType == "Octo" || frameType == "Octocopter") {
|
||||
elementId = "quad-octo";
|
||||
} else if (frameType == "OctoX" || frameType == "Octocopter X") {
|
||||
elementId = "quad-octo-X";
|
||||
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
|
||||
elementId = "quad-octo-v";
|
||||
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
|
||||
@ -899,6 +995,23 @@ void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
|
||||
configData.multi.VTOLMotorW = index;
|
||||
} else if (motor == QString("VTOLMotorNW")) {
|
||||
configData.multi.VTOLMotorNW = index;
|
||||
//OctoX
|
||||
} else if (motor == QString("VTOLMotorNNE")) {
|
||||
configData.multi.VTOLMotorNNE = index;
|
||||
} else if (motor == QString("VTOLMotorENE")) {
|
||||
configData.multi.VTOLMotorENE = index;
|
||||
} else if (motor == QString("VTOLMotorESE")) {
|
||||
configData.multi.VTOLMotorESE = index;
|
||||
} else if (motor == QString("VTOLMotorSSE")) {
|
||||
configData.multi.VTOLMotorSSE = index;
|
||||
} else if (motor == QString("VTOLMotorSSW")) {
|
||||
configData.multi.VTOLMotorSSW = index;
|
||||
} else if (motor == QString("VTOLMotorWSW")) {
|
||||
configData.multi.VTOLMotorWSW = index;
|
||||
} else if (motor == QString("VTOLMotorWNW")) {
|
||||
configData.multi.VTOLMotorWNW = index;
|
||||
} else if (motor == QString("VTOLMotorNNW")) {
|
||||
configData.multi.VTOLMotorNNW = index;
|
||||
}
|
||||
}
|
||||
setConfigData(configData);
|
||||
|
@ -42,6 +42,15 @@ typedef struct {
|
||||
uint VTOLMotorNE : 4;
|
||||
uint VTOLMotorSW : 4;
|
||||
uint VTOLMotorSE : 4; // 32 bits
|
||||
/* OctoX */
|
||||
uint VTOLMotorNNE : 4;
|
||||
uint VTOLMotorENE : 4;
|
||||
uint VTOLMotorESE : 4;
|
||||
uint VTOLMotorSSE : 4;
|
||||
uint VTOLMotorSSW : 4;
|
||||
uint VTOLMotorWSW : 4;
|
||||
uint VTOLMotorWNW : 4;
|
||||
uint VTOLMotorNNW : 4; // 32 bits
|
||||
uint TRIYaw : 4;
|
||||
quint32 padding : 28; // 64 bits
|
||||
quint32 padding1;
|
||||
|
@ -85,6 +85,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXX:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXP:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTO:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXAX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXACOAX:
|
||||
case SystemSettings::AIRFRAMETYPE_HEXA:
|
||||
@ -263,9 +264,11 @@ int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
} else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X"
|
||||
|| frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter"
|
||||
|| frameType == "HexaX" || frameType == "Hexacopter X" || frameType == "HexaCoax"
|
||||
|| frameType == "HexaH" || frameType == "Hexacopter H"
|
||||
|| frameType == "Hexacopter Y6" || frameType == "Octo" || frameType == "Octocopter" || frameType == "OctoV"
|
||||
|| frameType == "Octocopter V" || frameType == "OctoCoaxP" || frameType == "Octo Coax +"
|
||||
|| frameType == "HexaH" || frameType == "Hexacopter H" || frameType == "Hexacopter Y6"
|
||||
|| frameType == "Octo" || frameType == "Octocopter"
|
||||
|| frameType == "OctoX" || frameType == "Octocopter X"
|
||||
|| frameType == "OctoV" || frameType == "Octocopter V"
|
||||
|| frameType == "OctoCoaxP" || frameType == "Octo Coax +"
|
||||
|| frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
|
||||
return ConfigVehicleTypeWidget::MULTIROTOR;
|
||||
} else if (frameType == "HeliCP") {
|
||||
|
File diff suppressed because one or more lines are too long
Before Width: | Height: | Size: 899 KiB After Width: | Height: | Size: 898 KiB |
@ -206,6 +206,7 @@ void VehicleConfigurationHelper::applyVehicleConfiguration()
|
||||
setupHexaCopter();
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V:
|
||||
@ -282,6 +283,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V:
|
||||
@ -1089,62 +1091,71 @@ void VehicleConfigurationHelper::setupOctoCopter()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTO;
|
||||
|
||||
// OctoP according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
//M1{ 1 , 0 , -1 },
|
||||
//M2{ 0.71,-0.71, 1 },
|
||||
//M3{ 0 ,-1 , -1 },
|
||||
//M4{ -0.71,-0.71, 1 },
|
||||
//M5{ -1 , 0 , -1 },
|
||||
//M6{ -0.71, 0.71, 1 },
|
||||
//M7{ 0 , 1 , -1 },
|
||||
//M8{ 0.71, 0.71, 1 }
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = 0;
|
||||
channels[0].pitch = 33;
|
||||
channels[0].yaw = -25;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -33;
|
||||
channels[1].pitch = 33;
|
||||
channels[1].yaw = 25;
|
||||
channels[1].roll = -71;
|
||||
channels[1].pitch = 71;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -33;
|
||||
channels[2].roll = -71;
|
||||
channels[2].pitch = 0;
|
||||
channels[2].yaw = -25;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = -33;
|
||||
channels[3].pitch = -33;
|
||||
channels[3].yaw = 25;
|
||||
channels[3].roll = -71;
|
||||
channels[3].pitch = -71;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 0;
|
||||
channels[4].pitch = -33;
|
||||
channels[4].yaw = -25;
|
||||
channels[4].pitch = -100;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 33;
|
||||
channels[5].pitch = -33;
|
||||
channels[5].yaw = 25;
|
||||
channels[5].roll = 71;
|
||||
channels[5].pitch = -71;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
channels[6].type = MIXER_TYPE_MOTOR;
|
||||
channels[6].throttle1 = 100;
|
||||
channels[6].throttle2 = 0;
|
||||
channels[6].roll = 33;
|
||||
channels[6].roll = 100;
|
||||
channels[6].pitch = 0;
|
||||
channels[6].yaw = -25;
|
||||
channels[6].yaw = -100;
|
||||
|
||||
channels[7].type = MIXER_TYPE_MOTOR;
|
||||
channels[7].throttle1 = 100;
|
||||
channels[7].throttle2 = 0;
|
||||
channels[7].roll = 33;
|
||||
channels[7].pitch = 33;
|
||||
channels[7].yaw = 25;
|
||||
channels[7].roll = 71;
|
||||
channels[7].pitch = 71;
|
||||
channels[7].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorN = 1;
|
||||
guiSettings.multi.VTOLMotorNE = 2;
|
||||
@ -1157,6 +1168,86 @@ void VehicleConfigurationHelper::setupOctoCopter()
|
||||
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTOX;
|
||||
// OctoX according to new mixer table and pitch-roll-yaw mixing at 100%
|
||||
// Pitch Roll Yaw
|
||||
//M1{ 1 ,-0.41, -1 },
|
||||
//M2{ 0.41, -1 , 1 },
|
||||
//M3{ -0.41, -1 , -1 },
|
||||
//M4{ -1 ,-0.41, 1 },
|
||||
//M5{ -1 , 0.41, -1 },
|
||||
//M6{ -0.41, 1 , 1 },
|
||||
//M7{ 0.41, 1 , -1 },
|
||||
//M8{ 1 , 0.41, 1 }
|
||||
channels[0].type = MIXER_TYPE_MOTOR;
|
||||
channels[0].throttle1 = 100;
|
||||
channels[0].throttle2 = 0;
|
||||
channels[0].roll = -41;
|
||||
channels[0].pitch = 100;
|
||||
channels[0].yaw = -100;
|
||||
|
||||
channels[1].type = MIXER_TYPE_MOTOR;
|
||||
channels[1].throttle1 = 100;
|
||||
channels[1].throttle2 = 0;
|
||||
channels[1].roll = -100;
|
||||
channels[1].pitch = 41;
|
||||
channels[1].yaw = 100;
|
||||
|
||||
channels[2].type = MIXER_TYPE_MOTOR;
|
||||
channels[2].throttle1 = 100;
|
||||
channels[2].throttle2 = 0;
|
||||
channels[2].roll = -100;
|
||||
channels[2].pitch = -41;
|
||||
channels[2].yaw = -100;
|
||||
|
||||
channels[3].type = MIXER_TYPE_MOTOR;
|
||||
channels[3].throttle1 = 100;
|
||||
channels[3].throttle2 = 0;
|
||||
channels[3].roll = -41;
|
||||
channels[3].pitch = -100;
|
||||
channels[3].yaw = 100;
|
||||
|
||||
channels[4].type = MIXER_TYPE_MOTOR;
|
||||
channels[4].throttle1 = 100;
|
||||
channels[4].throttle2 = 0;
|
||||
channels[4].roll = 41;
|
||||
channels[4].pitch = -100;
|
||||
channels[4].yaw = -100;
|
||||
|
||||
channels[5].type = MIXER_TYPE_MOTOR;
|
||||
channels[5].throttle1 = 100;
|
||||
channels[5].throttle2 = 0;
|
||||
channels[5].roll = 100;
|
||||
channels[5].pitch = -41;
|
||||
channels[5].yaw = 100;
|
||||
|
||||
channels[6].type = MIXER_TYPE_MOTOR;
|
||||
channels[6].throttle1 = 100;
|
||||
channels[6].throttle2 = 0;
|
||||
channels[6].roll = 100;
|
||||
channels[6].pitch = 41;
|
||||
channels[6].yaw = -100;
|
||||
|
||||
channels[7].type = MIXER_TYPE_MOTOR;
|
||||
channels[7].throttle1 = 100;
|
||||
channels[7].throttle2 = 0;
|
||||
channels[7].roll = 41;
|
||||
channels[7].pitch = 100;
|
||||
channels[7].yaw = 100;
|
||||
|
||||
guiSettings.multi.VTOLMotorNNE = 1;
|
||||
guiSettings.multi.VTOLMotorENE = 2;
|
||||
guiSettings.multi.VTOLMotorESE = 3;
|
||||
guiSettings.multi.VTOLMotorSSE = 4;
|
||||
guiSettings.multi.VTOLMotorSSW = 5;
|
||||
guiSettings.multi.VTOLMotorWSW = 6;
|
||||
guiSettings.multi.VTOLMotorWNW = 7;
|
||||
guiSettings.multi.VTOLMotorNNW = 8;
|
||||
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X:
|
||||
{
|
||||
frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXX;
|
||||
|
@ -59,8 +59,8 @@ public:
|
||||
enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE };
|
||||
enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS,
|
||||
MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO,
|
||||
MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON,
|
||||
FIXED_WING_VTAIL, HELI_CCPM };
|
||||
MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS,
|
||||
FIXED_WING_AILERON, FIXED_WING_VTAIL, HELI_CCPM };
|
||||
enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN };
|
||||
enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN };
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
<xml>
|
||||
<object name="SystemSettings" singleinstance="true" settings="true" category="System">
|
||||
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
|
||||
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,HexaH,OctoV,OctoCoaxP,OctoCoaxX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="QuadX"/>
|
||||
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,HexaH,OctoV,OctoCoaxP,OctoCoaxX,OctoX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="QuadX"/>
|
||||
<field name="ThrustControl" units="" type="enum" elements="1" options="Throttle,Collective,None" defaultvalue="Throttle" />
|
||||
<!-- Which way the vehicle controls its thrust. Can be through
|
||||
"Throttle" (quadcopter, simple brushless planes,
|
||||
|
Loading…
x
Reference in New Issue
Block a user