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

ArduCopter: fix few broken frames #19010

Merged
merged 2 commits into from
Nov 23, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -6817,9 +6817,6 @@ def fly_each_frame(self):
vinfo = vehicleinfo.VehicleInfo()
copter_vinfo_options = vinfo.options[self.vehicleinfo_key()]
known_broken_frames = {
'cwx': "missing defaults file",
'deca-cwx': 'missing defaults file',
'djix': "missing defaults file",
'heli-compound': "wrong binary, different takeoff regime",
'heli-dual': "wrong binary, different takeoff regime",
'heli': "wrong binary, different takeoff regime",
Expand Down
1 change: 1 addition & 0 deletions Tools/autotest/default_params/copter-cwx.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
FRAME_TYPE 14
1 change: 1 addition & 0 deletions Tools/autotest/default_params/copter-deca-cwx.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
FRAME_TYPE 14
1 change: 1 addition & 0 deletions Tools/autotest/default_params/copter-djix.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
FRAME_TYPE 13
6 changes: 5 additions & 1 deletion Tools/autotest/pysim/vehicleinfo.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,11 @@ def __init__(self):
},
"deca-cwx": {
"waf_target": "bin/arducopter",
"default_params_filename": "default_params/copter.parm",
"default_params_filename": [
"default_params/copter.parm",
"default_params/copter-deca.parm",
"default_params/copter-deca-cwx.parm"
],
},
"tri": {
"waf_target": "bin/arducopter",
Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_Motors/AP_MotorsMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1181,8 +1181,9 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
add_motors(motors, ARRAY_SIZE(motors));
break;
}
case MOTOR_FRAME_TYPE_X: {
_frame_type_string = "X";
case MOTOR_FRAME_TYPE_X:
case MOTOR_FRAME_TYPE_CW_X: {
IamPete1 marked this conversation as resolved.
Show resolved Hide resolved
_frame_type_string = "X/CW_X";
static const AP_MotorsMatrix::MotorDef motors[] {
{ 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 },
{ 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 },
Expand Down