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

432 new mixing system #438

Draft
wants to merge 42 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 33 commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
a45aa08
Adds option to use mixer based on motor positions and motor parameters.
JMoore5353 Aug 5, 2024
8ddf21e
Adds option to use mixer based on motor positions and motor parameters.
JMoore5353 Aug 5, 2024
4750c9c
Merge branch '432-new-mixing-system' of github.com:rosflight/rosfligh…
JMoore5353 Aug 5, 2024
70e7c9b
changed controller to output forces and torques
JMoore5353 Aug 8, 2024
f41077f
added parameters for the new mixing matrix calculations
JMoore5353 Aug 8, 2024
2caff09
Added custom mixer that uses Ch. 14 mixer equations. Also uses Ch. 4 …
JMoore5353 Aug 8, 2024
ab5ec00
added maximum throttle param from RC controller to maintain controlla…
JMoore5353 Aug 12, 2024
20e5d63
Scales thrust commands by RC_MAX_THROTTLE to maintain controllability
JMoore5353 Aug 14, 2024
c068882
Computes the mixing matrix using the SVD, which doesn't dynamically a…
JMoore5353 Aug 14, 2024
fbc2fe3
fixing code style
JMoore5353 Aug 14, 2024
69dc3af
return type qualifier fix
JMoore5353 Aug 14, 2024
cc75f32
added libeigen3-dev to workflow runs
JMoore5353 Aug 15, 2024
04d14e3
Added Eigen dependency to all boards.
JMoore5353 Aug 15, 2024
b28b910
Moved Eigen package to common/CMakeLists.txt
JMoore5353 Aug 15, 2024
b76ede7
Added hardcoded, precomputed mixing matrices for standard aircraft
JMoore5353 Aug 15, 2024
ef17b47
fixed include error
JMoore5353 Aug 15, 2024
a6ced22
Added find eigen call back
JMoore5353 Aug 15, 2024
6c5e163
Moved Eigen dependency back to the rosflight_firmware CMakeLists.txt
JMoore5353 Aug 27, 2024
6821d10
removed the quadplane mixing matrix to avoid confusion since it doesn…
JMoore5353 Oct 9, 2024
537d75b
added flag to switch between fixedwing mixing and multirotor mixing.
JMoore5353 Oct 14, 2024
10ebc1d
default F behavior for fixedwings is passthrough to mixer instead of …
JMoore5353 Oct 14, 2024
a571d4b
refactored some names and got rid of unused dependencies
JMoore5353 Oct 15, 2024
e0ece54
changed the mixer pwm outputs to be compatible with Varmint and Pixra…
JMoore5353 Oct 15, 2024
ed08c3b
recomputed canned mixers and added mixer parameters to the firmware
JMoore5353 Oct 29, 2024
a3ac22b
removed unused parameters and fixed mixing matrix paramter names
JMoore5353 Oct 29, 2024
3d62203
Update the input forces to include Fx and Fy
JMoore5353 Nov 7, 2024
180a3cb
added mixer header values to the parameter list
JMoore5353 Nov 7, 2024
8816fd8
fixed Fz for the canned mixers, since we are in NED frame
JMoore5353 Nov 11, 2024
274df44
changed mixer indices for clarity and fixed some bugs when using cust…
JMoore5353 Nov 11, 2024
bcd88bd
fixed aux channels not getting initialized. Changed the way servos ar…
JMoore5353 Nov 11, 2024
c6c66db
Added parameter to choose which axis the RC throttle corresponds to
JMoore5353 Nov 12, 2024
9d85c98
added support for secondary mixer
JMoore5353 Nov 26, 2024
be8a43a
some updates to the unit tests
JMoore5353 Nov 26, 2024
8dfbba3
minor code cleanup
JMoore5353 Dec 6, 2024
935548d
added descriptions to some parameters
JMoore5353 Dec 11, 2024
9416b66
changed eigen dependency to be fetch content so it is more platform i…
JMoore5353 Dec 16, 2024
0ee7dde
removed iostream dependency and dead function calls
JMoore5353 Dec 16, 2024
4173d59
removed air density as a parameter. Using ideal gas law
JMoore5353 Dec 17, 2024
ff54382
renamed NONE to AUX since it is only used for AUX channels
JMoore5353 Dec 17, 2024
e0eee63
added error checking for RC F axis selection
JMoore5353 Dec 17, 2024
1f01b73
reworked the way mixers were assigned to use the enums instead of the…
JMoore5353 Dec 17, 2024
100fe33
replaced the load parameter methods with a loop
JMoore5353 Dec 17, 2024
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
2 changes: 1 addition & 1 deletion .github/workflows/pre-release.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ jobs:
- name: checkout submodules
run: git submodule update --init --recursive
- name: install toolchain
run: sudo apt -y install gcc-arm-none-eabi
run: sudo apt -y install gcc-arm-none-eabi libeigen3-dev
- name: check toolchain
run: arm-none-eabi-gcc --version
- name: build varmint
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/release.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ jobs:
- name: checkout submodules
run: git submodule update --init --recursive
- name: install toolchain
run: sudo apt -y install gcc-arm-none-eabi
run: sudo apt -y install gcc-arm-none-eabi libeigen3-dev
- name: check toolchain
run: arm-none-eabi-gcc --version
- name: build varmint
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/varmint_firmware.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ jobs:
- name: checkout submodules
run: git submodule update --init --recursive
- name: install toolchain
run: sudo apt -y install gcc-arm-none-eabi
run: sudo apt -y install gcc-arm-none-eabi libeigen3-dev
- name: check toolchain
run: arm-none-eabi-gcc --version
- name: build varmint
Expand Down
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ if("${GIT_VERSION_HASH}" STREQUAL "")
endif()

### source files ###
find_package(Eigen3 REQUIRED)
include_directories(${EIGEN3_INCLUDE_DIRS})

include_directories(
include
Expand Down
22 changes: 13 additions & 9 deletions comms/mavlink/mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -487,15 +487,19 @@ void Mavlink::handle_msg_offboard_control(const mavlink_message_t * const msg)
return;
}

control.x.value = ctrl.x;
control.y.value = ctrl.y;
control.z.value = ctrl.z;
control.F.value = ctrl.F;

control.x.valid = !(ctrl.ignore & IGNORE_VALUE1);
control.y.valid = !(ctrl.ignore & IGNORE_VALUE2);
control.z.valid = !(ctrl.ignore & IGNORE_VALUE3);
control.F.valid = !(ctrl.ignore & IGNORE_VALUE4);
control.Qx.value = ctrl.Qx;
control.Qy.value = ctrl.Qy;
control.Qz.value = ctrl.Qz;
control.Fx.value = ctrl.Fx;
control.Fy.value = ctrl.Fy;
control.Fz.value = ctrl.Fz;

control.Qx.valid = !(ctrl.ignore & IGNORE_VALUE1);
control.Qy.valid = !(ctrl.ignore & IGNORE_VALUE2);
control.Qz.valid = !(ctrl.ignore & IGNORE_VALUE3);
control.Fx.valid = !(ctrl.ignore & IGNORE_VALUE4);
control.Fy.valid = !(ctrl.ignore & IGNORE_VALUE5);
control.Fz.valid = !(ctrl.ignore & IGNORE_VALUE6);

if (listener_ != nullptr) { listener_->offboard_control_callback(control); }
}
Expand Down
56 changes: 41 additions & 15 deletions include/command_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ typedef enum
{
RATE, // Channel is is in rate mode (mrad/s)
ANGLE, // Channel command is in angle mode (mrad)
THROTTLE, // Channel is direcly controlling throttle max/1000
THROTTLE, // Channel is controlling throttle setting, which will be converted to force
PASSTHROUGH, // Channel directly passes PWM input to the mixer
} control_type_t;

Expand All @@ -58,13 +58,22 @@ typedef struct
float value; // The value of the channel
} control_channel_t;

typedef enum
{
X_AXIS,
Y_AXIS,
Z_AXIS,
} rc_f_axis_t;

typedef struct
{
uint32_t stamp_ms;
control_channel_t x;
control_channel_t y;
control_channel_t z;
control_channel_t F;
control_channel_t Qx;
control_channel_t Qy;
control_channel_t Qz;
control_channel_t Fx;
control_channel_t Fy;
control_channel_t Fz;
} control_t;

class CommandManager : public ParamListenerInterface
Expand All @@ -77,38 +86,50 @@ class CommandManager : public ParamListenerInterface
control_channel_t * combined;
} mux_t;

mux_t muxes[4] = {{&rc_command_.x, &offboard_command_.x, &combined_command_.x},
{&rc_command_.y, &offboard_command_.y, &combined_command_.y},
{&rc_command_.z, &offboard_command_.z, &combined_command_.z},
{&rc_command_.F, &offboard_command_.F, &combined_command_.F}};
mux_t muxes[6] = {{&rc_command_.Qx, &offboard_command_.Qx, &combined_command_.Qx},
{&rc_command_.Qy, &offboard_command_.Qy, &combined_command_.Qy},
{&rc_command_.Qz, &offboard_command_.Qz, &combined_command_.Qz},
{&rc_command_.Fx, &offboard_command_.Fx, &combined_command_.Fx},
{&rc_command_.Fy, &offboard_command_.Fy, &combined_command_.Fy},
{&rc_command_.Fz, &offboard_command_.Fz, &combined_command_.Fz}};

// clang-format off
control_t rc_command_ = {0,
{false, ANGLE, 0.0},
{false, ANGLE, 0.0},
{false, RATE, 0.0},
{false, THROTTLE, 0.0},
{false, THROTTLE, 0.0},
{false, THROTTLE, 0.0}};
control_t offboard_command_ = {0,
{false, ANGLE, 0.0},
{false, ANGLE, 0.0},
{false, RATE, 0.0},
{false, THROTTLE, 0.0},
iandareid marked this conversation as resolved.
Show resolved Hide resolved
{false, THROTTLE, 0.0},
{false, THROTTLE, 0.0}};
control_t combined_command_ = {0,
{false, ANGLE, 0.0},
{false, ANGLE, 0.0},
{false, RATE, 0.0},
{false, THROTTLE, 0.0},
{false, THROTTLE, 0.0},
{false, THROTTLE, 0.0}};

control_t multirotor_failsafe_command_ = {0,
{true, ANGLE, 0.0},
{true, ANGLE, 0.0},
{true, RATE, 0.0},
{true, THROTTLE, 0.0},
{true, THROTTLE, 0.0},
{true, THROTTLE, 0.0}};
control_t fixedwing_failsafe_command_ = {0,
{true, PASSTHROUGH, 0.0},
{true, PASSTHROUGH, 0.0},
{true, PASSTHROUGH, 0.0},
{true, THROTTLE, 0.0}};
{true, PASSTHROUGH, 0.0},
{true, PASSTHROUGH, 0.0},
{true, PASSTHROUGH, 0.0}};
// clang-format on

typedef enum
Expand All @@ -119,10 +140,12 @@ class CommandManager : public ParamListenerInterface

enum MuxChannel
{
MUX_X,
MUX_Y,
MUX_Z,
MUX_F,
MUX_QX,
MUX_QY,
MUX_QZ,
MUX_FX,
MUX_FY,
MUX_FZ,
};

typedef struct
Expand All @@ -138,7 +161,8 @@ class CommandManager : public ParamListenerInterface
ROSflight & RF_;

bool new_command_;
bool rc_override_;
bool rc_throttle_override_;
bool rc_attitude_override_;

control_t & failsafe_command_;

Expand All @@ -157,6 +181,8 @@ class CommandManager : public ParamListenerInterface
void init();
bool run();
bool rc_override_active();
bool rc_throttle_override_active();
bool rc_attitude_override_active();
bool offboard_control_active();
void set_new_offboard_command(control_t new_offboard_command);
void set_new_rc_command(control_t new_rc_command);
Expand Down
18 changes: 12 additions & 6 deletions include/controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,19 +51,23 @@ class Controller : public ParamListenerInterface
public:
struct Output
{
float F;
float x;
float y;
float z;
float Fx;
float Fy;
float Fz;
float Qx;
float Qy;
float Qz;
};

Controller(ROSflight & rf);

inline const Output & output() const { return output_; }
inline float max_thrust() const { return max_thrust_; }

void init();
void run();

void calculate_max_thrust();
void calculate_equilbrium_torque_from_rc();
void param_change_callback(uint16_t param_id) override;

Expand Down Expand Up @@ -92,8 +96,8 @@ class Controller : public ParamListenerInterface

ROSflight & RF_;

turbomath::Vector run_pid_loops(uint32_t dt, const Estimator::State & state,
const control_t & command, bool update_integrators);
Controller::Output run_pid_loops(uint32_t dt, const Estimator::State & state,
const control_t & command, bool update_integrators);

Output output_;

Expand All @@ -103,6 +107,8 @@ class Controller : public ParamListenerInterface
PID pitch_rate_;
PID yaw_rate_;

float max_thrust_;

uint64_t prev_time_us_;
};

Expand Down
10 changes: 6 additions & 4 deletions include/interface/comm_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,10 +85,12 @@ class CommLinkInterface
};

Mode mode;
Channel x;
Channel y;
Channel z;
Channel F;
Channel Qx;
Channel Qy;
Channel Qz;
Channel Fx;
Channel Fy;
Channel Fz;
};

struct AuxCommand
Expand Down
Loading
Loading