Skip to content

Commit

Permalink
Copter: implement suggested changes
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed May 14, 2024
1 parent 27b3cfe commit 13bbc1f
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 8 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include "Copter.h"
#include <AP_Math/chirp.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h> // TODO why is this needed if Copter.h includes this
#include <AP_Math/control.h>

class Parameters;
class ParametersG2;

Expand Down
21 changes: 14 additions & 7 deletions ArduCopter/mode_systemid.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "Copter.h"
#include <AP_Math/control.h>

#if MODE_SYSTEMID_ENABLED == ENABLED

Expand Down Expand Up @@ -129,8 +130,7 @@ bool ModeSystemId::init(bool ignore_checks)
}
Vector3f curr_pos;
curr_pos = inertial_nav.get_position_neu_cm();
target_pos.x = curr_pos.x;
target_pos.y = curr_pos.y;
target_pos = curr_pos.xy();
}

att_bf_feedforward = attitude_control->get_bf_feedforward();
Expand Down Expand Up @@ -428,11 +428,18 @@ bool ModeSystemId::is_poscontrol_axis_type() const
{
bool ret = false;

if ((AxisType)axis.get() == AxisType::DISTURB_POS_LAT || (AxisType)axis.get() == AxisType::DISTURB_POS_LONG
|| (AxisType)axis.get() == AxisType::DISTURB_VEL_LAT || (AxisType)axis.get() == AxisType::DISTURB_VEL_LONG
|| (AxisType)axis.get() == AxisType::INPUT_LOITER_LAT || (AxisType)axis.get() == AxisType::INPUT_LOITER_LONG) {
ret = true;
}
switch ((AxisType)axis.get()) {
case AxisType::DISTURB_POS_LAT:
case AxisType::DISTURB_POS_LONG:
case AxisType::DISTURB_VEL_LAT:
case AxisType::DISTURB_VEL_LONG:
case AxisType::INPUT_LOITER_LAT:
case AxisType::INPUT_LOITER_LONG:
ret = true;
break;
default:
break;
}

return ret;
}
Expand Down

0 comments on commit 13bbc1f

Please sign in to comment.