Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bidirectional Control For Motors #10778

Draft
wants to merge 13 commits into
base: master
Choose a base branch
from
2 changes: 1 addition & 1 deletion src/AutoPilotPlugins/PX4/ActuatorComponent.qml
Original file line number Diff line number Diff line change
Expand Up @@ -252,7 +252,7 @@ SetupPage {
stopTimer();
for (var channelIdx=0; channelIdx<sliderRepeater.count; channelIdx++) {
var channelSlider = sliderRepeater.itemAt(channelIdx);
if (channelSlider.channel.isMotor) {
if (channelSlider.channel.isMotor && !channelSlider.channel.isBidirectional) {
channelSlider.value = sliderValue;
}
}
Expand Down
6 changes: 3 additions & 3 deletions src/Vehicle/Actuators/ActuatorTesting.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,14 +41,14 @@ void ActuatorTest::updateFunctions(const QList<Actuator*> &actuators)

Actuator* motorActuator{nullptr};
for (const auto& actuator : actuators) {
if (actuator->isMotor()) {
if (actuator->isMotor() && !actuator->isBidirectional()) {
motorActuator = actuator;
}
_actuators->append(actuator);
}
if (motorActuator) {
_allMotorsActuator = new Actuator(this, tr("All Motors"), motorActuator->min(), motorActuator->max(), motorActuator->defaultValue(),
motorActuator->function(), true);
_allMotorsActuator = new Actuator(this, tr("All Standard Motors"), motorActuator->min(), motorActuator->max(), motorActuator->defaultValue(),
motorActuator->function(), true, false);
}
resetStates();

Expand Down
7 changes: 5 additions & 2 deletions src/Vehicle/Actuators/ActuatorTesting.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,23 +24,25 @@ class Actuator : public QObject
{
Q_OBJECT
public:
Actuator(QObject* parent, const QString& label, float min, float max, float defaultValue, int function, bool isMotor)
Actuator(QObject* parent, const QString& label, float min, float max, float defaultValue, int function, bool isMotor, bool isBidirectional)
: QObject(parent), _label(label), _min(min), _max(max), _defaultValue(defaultValue), _function(function),
_isMotor(isMotor) {}
_isMotor(isMotor), _isBidirectional(isBidirectional) {}

Q_PROPERTY(QString label READ label CONSTANT)
Q_PROPERTY(float min READ min CONSTANT)
Q_PROPERTY(float max READ max CONSTANT)
Q_PROPERTY(float defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(int function READ function CONSTANT)
Q_PROPERTY(bool isMotor READ isMotor CONSTANT)
Q_PROPERTY(bool isBidirectional READ isBidirectional CONSTANT)

const QString& label() const { return _label; }
float min() const { return _min; }
float max() const { return _max; }
float defaultValue() const { return _defaultValue; }
int function() const { return _function; }
bool isMotor() const { return _isMotor; }
bool isBidirectional() const { return _isBidirectional; }

private:
const QString _label;
Expand All @@ -49,6 +51,7 @@ class Actuator : public QObject
const float _defaultValue;
const int _function;
const bool _isMotor;
const bool _isBidirectional;
};

class ActuatorTest : public QObject
Expand Down
28 changes: 25 additions & 3 deletions src/Vehicle/Actuators/Actuators.cc
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,7 @@ void Actuators::parametersChanged()
QList<ActuatorTesting::Actuator*> actuators;
QSet<int> uniqueConfiguredFunctions;
const Mixer::ActuatorTypes &actuatorTypes = _mixer.actuatorTypes();
int num_motor = 0;
for (int function : allFunctions) {
if (uniqueConfiguredFunctions.find(function) != uniqueConfiguredFunctions.end()) { // only add once
continue;
Expand All @@ -221,9 +222,30 @@ void Actuators::parametersChanged()
const Mixer::ActuatorType& actuatorType = actuatorTypes[actuatorTypeName];
if (function >= actuatorType.functionMin && function <= actuatorType.functionMax) {
bool isMotor = ActuatorGeometry::typeFromStr(actuatorTypeName) == ActuatorGeometry::Type::Motor;
bool isBidirectional = false;
float min_value = actuatorType.values.min;
float default_value = actuatorType.values.defaultVal;

if(isMotor){
QString bidirectional_param("CA_R_REV");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We cannot use hardcoded parameter values here, as it makes it PX4-specific, and it will break easily.

Rather we need to set the reversible function on the PX4 side for the parameter, and then make use of it here. -> https://github.com/mavlink/mavlink/blob/master/component_metadata/actuators.schema.json#L63

quint8 bitset_bidirectional = getFact(bidirectional_param)->rawValue().toInt();
quint8 is_bidi = (bitset_bidirectional >> num_motor) & 0b1;

if(is_bidi == 1){

min_value = -1.0f;
default_value = 0.0f;
isBidirectional = true;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The idea is that if reversible is set (https://github.com/mavlink/mavlink/blob/master/component_metadata/actuators.schema.json#L37), then the range [-max, -min] should be used for the reversible part. So you don't have to hardcode values.


}
num_motor++;

}

// qDebug() << "testinng: " << actuatorType.values.min << actuatorType.values.max << actuatorType.values.defaultVal;
actuators.append(
new ActuatorTesting::Actuator(&_actuatorTest, label, actuatorType.values.min, actuatorType.values.max,
actuatorType.values.defaultVal, function, isMotor));
new ActuatorTesting::Actuator(&_actuatorTest, label, min_value, actuatorType.values.max,
default_value, function, isMotor, isBidirectional));
found = true;
break;
}
Expand All @@ -232,7 +254,7 @@ void Actuators::parametersChanged()
const Mixer::ActuatorType& actuatorType = actuatorTypes["DEFAULT"];
actuators.append(
new ActuatorTesting::Actuator(&_actuatorTest, label, actuatorType.values.min, actuatorType.values.max,
actuatorType.values.defaultVal, function, false));
actuatorType.values.defaultVal, function, false, false));
}
}
}
Expand Down