Commit 9d18a986 authored by Bryant's avatar Bryant

The joystick code now understands if a UAS can reverse or not (based on...

The joystick code now understands if a UAS can reverse or not (based on UASInterface::systemCanReverse) and scales the joystick input accordingly. This isn't ideal on auto-centering axes and so the limit-range code should be brought back as an option for the throttle channel.
parent b6d9f23b
...@@ -29,6 +29,7 @@ JoystickInput::JoystickInput() : ...@@ -29,6 +29,7 @@ JoystickInput::JoystickInput() :
sdlJoystickMin(-32768.0f), sdlJoystickMin(-32768.0f),
sdlJoystickMax(32767.0f), sdlJoystickMax(32767.0f),
uas(NULL), uas(NULL),
uasCanReverse(false),
done(false), done(false),
rollAxis(-1), rollAxis(-1),
pitchAxis(-1), pitchAxis(-1),
...@@ -100,6 +101,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -100,6 +101,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
disconnect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int))); disconnect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int)));
disconnect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int))); disconnect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int)));
} }
uasCanReverse = false;
} }
this->uas = uas; this->uas = uas;
...@@ -110,6 +112,8 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -110,6 +112,8 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
if(tmp) { if(tmp) {
connect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int))); connect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int)));
connect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int))); connect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int)));
uasCanReverse = tmp->systemCanReverse();
qDebug() << "Current system can reverse: " << uasCanReverse;
} }
} }
} }
...@@ -153,8 +157,9 @@ void JoystickInput::init() ...@@ -153,8 +157,9 @@ void JoystickInput::init()
// And attach to the first joystick found to start. // And attach to the first joystick found to start.
setActiveJoystick(0); setActiveJoystick(0);
// Make sure active UAS is set // Make sure the active UAS is set and that we're tracking UAS changes.
setActiveUAS(UASManager::instance()->getActiveUAS()); setActiveUAS(UASManager::instance()->getActiveUAS());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
} }
void JoystickInput::shutdown() void JoystickInput::shutdown()
...@@ -198,7 +203,14 @@ void JoystickInput::run() ...@@ -198,7 +203,14 @@ void JoystickInput::run()
axisValue = (axisValue - calibrationPositive[i]) / (calibrationNegative[i] - calibrationPositive[i]); axisValue = (axisValue - calibrationPositive[i]) / (calibrationNegative[i] - calibrationPositive[i]);
} }
axisValue = 1.0f - axisValue; axisValue = 1.0f - axisValue;
axisValue = axisValue * 2.0f - 1.0f;
// Only map the throttle into [0:1] if the UAS can reverse.
if (uasCanReverse || throttleAxis != i)
{
axisValue = axisValue * 2.0f - 1.0f;
} else {
int a = 8;
}
// Bound rounding errors // Bound rounding errors
if (axisValue > 1.0f) axisValue = 1.0f; if (axisValue > 1.0f) axisValue = 1.0f;
......
...@@ -139,7 +139,8 @@ protected: ...@@ -139,7 +139,8 @@ protected:
double calibrationPositive[10]; double calibrationPositive[10];
double calibrationNegative[10]; double calibrationNegative[10];
SDL_Joystick* joystick; SDL_Joystick* joystick;
UASInterface* uas; UASInterface* uas; ///< Track the current UAS.
bool uasCanReverse; ///< Track whether the connect UAS can drive a reverse speed.
bool done; bool done;
// Store the mapping between axis numbers and the roll/pitch/yaw/throttle configuration. // Store the mapping between axis numbers and the roll/pitch/yaw/throttle configuration.
......
...@@ -2694,6 +2694,41 @@ int UAS::getSystemType() ...@@ -2694,6 +2694,41 @@ int UAS::getSystemType()
return this->type; return this->type;
} }
/**
* @brief Returns true for systems that can reverse. If the system has no control over position, it returns false as well.
* @return If the specified vehicle type can
*/
//bool UAS::systemCanReverse() const
//{
// switch(type)
// {
// case MAV_TYPE_GENERIC:
// case MAV_TYPE_FIXED_WING:
// case MAV_TYPE_ROCKET:
// case MAV_TYPE_FLAPPING_WING:
// // System types that don't have movement
// case MAV_TYPE_ANTENNA_TRACKER:
// case MAV_TYPE_GCS:
// case MAV_TYPE_FREE_BALLOON:
// default:
// return false;
// break;
// case MAV_TYPE_QUADROTOR:
// case MAV_TYPE_COAXIAL:
// case MAV_TYPE_HELICOPTER:
// case MAV_TYPE_AIRSHIP:
// case MAV_TYPE_GROUND_ROVER:
// case MAV_TYPE_SURFACE_BOAT:
// case MAV_TYPE_SUBMARINE:
// case MAV_TYPE_HEXAROTOR:
// case MAV_TYPE_OCTOROTOR:
// case MAV_TYPE_TRICOPTER:
// return true;
// break;
// }
//}
/** /**
* @param buttonIndex * @param buttonIndex
*/ */
......
#include "JoystickAxis.h" #include "JoystickAxis.h"
#include "JoystickInput.h" #include "JoystickInput.h"
#include "ui_JoystickAxis.h" #include "ui_JoystickAxis.h"
#include "UASManager.h"
#include <QString> #include <QString>
JoystickAxis::JoystickAxis(int id, QWidget *parent) : JoystickAxis::JoystickAxis(int id, QWidget *parent) :
...@@ -27,9 +28,22 @@ void JoystickAxis::setValue(float value) ...@@ -27,9 +28,22 @@ void JoystickAxis::setValue(float value)
void JoystickAxis::mappingComboBoxChanged(int newMapping) void JoystickAxis::mappingComboBoxChanged(int newMapping)
{ {
emit mappingChanged(id, (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping); emit mappingChanged(id, (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping);
this->setActiveUAS(UASManager::instance()->getActiveUAS());
} }
void JoystickAxis::inversionCheckBoxChanged(bool inverted) void JoystickAxis::inversionCheckBoxChanged(bool inverted)
{ {
emit inversionChanged(id, inverted); emit inversionChanged(id, inverted);
} }
void JoystickAxis::setActiveUAS(UASInterface* uas)
{
if (uas && !uas->systemCanReverse() && ui->comboBox->currentIndex() == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE)
{
ui->progressBar->setRange(0, 100);
}
else
{
ui->progressBar->setRange(-100, 100);
}
}
...@@ -27,6 +27,8 @@ public slots: ...@@ -27,6 +27,8 @@ public slots:
* @param value A value between -1.0 and 1.0. * @param value A value between -1.0 and 1.0.
*/ */
void setValue(float value); void setValue(float value);
/** @brief Specify the UAS that this axis should track for displaying throttle properly. */
void setActiveUAS(UASInterface* uas);
private: private:
int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput. int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput.
......
...@@ -121,6 +121,9 @@ ...@@ -121,6 +121,9 @@
<property name="textDirection"> <property name="textDirection">
<enum>QProgressBar::TopToBottom</enum> <enum>QProgressBar::TopToBottom</enum>
</property> </property>
<property name="format">
<string>%v</string>
</property>
</widget> </widget>
</item> </item>
<item> <item>
......
...@@ -144,6 +144,7 @@ void JoystickWidget::updateUIForJoystick(int id) ...@@ -144,6 +144,7 @@ void JoystickWidget::updateUIForJoystick(int id)
axis->setValue(joystick->getCurrentValueForAxis(i)); axis->setValue(joystick->getCurrentValueForAxis(i));
connect(axis, SIGNAL(mappingChanged(int,JoystickInput::JOYSTICK_INPUT_MAPPING)), this->joystick, SLOT(setAxisMapping(int,JoystickInput::JOYSTICK_INPUT_MAPPING))); connect(axis, SIGNAL(mappingChanged(int,JoystickInput::JOYSTICK_INPUT_MAPPING)), this->joystick, SLOT(setAxisMapping(int,JoystickInput::JOYSTICK_INPUT_MAPPING)));
connect(axis, SIGNAL(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool))); connect(axis, SIGNAL(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), axis, SLOT(setActiveUAS(UASInterface*)));
m_ui->axesLayout->addWidget(axis); m_ui->axesLayout->addWidget(axis);
axes.append(axis); axes.append(axis);
} }
......
...@@ -55,7 +55,9 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : ...@@ -55,7 +55,9 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
loadSettings(); loadSettings();
// Load default values and tooltips // Load default values and tooltips
loadParameterInfoCSV(uas->getAutopilotTypeName(), uas->getSystemTypeName()); QString hey(uas->getAutopilotTypeName());
QString hey2(uas->getSystemTypeName());
loadParameterInfoCSV(hey, hey2);
// Create tree widget // Create tree widget
tree = new QTreeWidget(this); tree = new QTreeWidget(this);
......
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