Skip to content

Commit

Permalink
[multirotorapi] make setControllerGains purevirtual; add non-impls in…
Browse files Browse the repository at this point in the history
… mavlink/arducopter
  • Loading branch information
madratman committed Mar 24, 2020
1 parent c2f4789 commit 52df395
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class MultirotorApiBase : public VehicleApiBase {
virtual void commandPosition(float x, float y, float z, const YawMode& yaw_mode) = 0;

/************************* set Controller Gains APIs *********************************/
virtual void setControllerGains(uint8_t controllerType, const vector<float>& kp, const vector<float>& ki, const vector<float>& kd) { }
virtual void setControllerGains(uint8_t controllerType, const vector<float>& kp, const vector<float>& ki, const vector<float>& kd) = 0;

/************************* State APIs *********************************/
virtual Kinematics::State getKinematicsEstimated() const = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,15 @@ class ArduCopterApi : public MultirotorApiBase {
return 0.5f; //measured in simulator by firing commands "MoveToLocation -x 0 -y 0" multiple times and looking at distance traveled
}

virtual void setControllerGains(uint8_t controllerType, const vector<float>& kp, const vector<float>& ki, const vector<float>& kd) override
{
unused(controllerType);
unused(kp);
unused(ki);
unused(kd);
Utils::log("Not Implemented: setControllerGains", Utils::kLogLevelInfo);
}

virtual void commandRollPitchYawrateThrottle(float roll, float pitch, float yaw_rate, float throttle) override
{
unused(roll);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -473,6 +473,15 @@ class MavLinkMultirotorApi : public MultirotorApiBase
}

protected: //methods
virtual void setControllerGains(uint8_t controllerType, const vector<float>& kp, const vector<float>& ki, const vector<float>& kd) override
{
unused(controllerType);
unused(kp);
unused(ki);
unused(kd);
Utils::log("Not Implemented: setControllerGains", Utils::kLogLevelInfo);
}

virtual void commandRollPitchYawZ(float roll, float pitch, float yaw, float z) override
{
if (target_height_ != -z) {
Expand Down

0 comments on commit 52df395

Please sign in to comment.