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

ACRO mode #634

Closed
wants to merge 150 commits into from
Closed
Show file tree
Hide file tree
Changes from 8 commits
Commits
Show all changes
150 commits
Select commit Hold shift + click to select a range
7f4f9a5
ACRO mode implemented
DrTon Jan 31, 2014
3651552
Merge branch 'beta' into acro2
DrTon Feb 1, 2014
2923bdf
commander: allow disarming in ACRO without landing (as in MANUAL)
DrTon Feb 1, 2014
77c6231
Merge branch 'beta' into acro2
DrTon Feb 1, 2014
c3e803c
Merge branch 'beta' into acro2
DrTon Feb 1, 2014
dfd4dc3
Merge branch 'beta' into acro2
DrTon Feb 2, 2014
2130087
mc_att_control: reset yaw setpoint after ACRO
DrTon Feb 2, 2014
b54b0ef
Merge branch 'beta' into acro2
DrTon Feb 4, 2014
6e7136c
rc_channels topic: bug fixed; sensors: minor cleanup
DrTon Feb 4, 2014
3b2b270
mavlink: custom mode ACRO added
DrTon Feb 4, 2014
e0fbb0f
Merge remote-tracking branch 'px4/beta' into acro2
julianoes Feb 10, 2014
b165e6b
Merge branch 'master' into acro2
DrTon Mar 8, 2014
edd16af
Add filter parameters and multicopter defaults to parametrize Pauls e…
LorenzMeier Apr 19, 2014
7b61c92
Renamed FW filter to EKF to express its generic properties, switched …
LorenzMeier Apr 19, 2014
dca1e7f
Decomission unmaintained position estimator
LorenzMeier Apr 19, 2014
ce56d75
Updated filter to most recent version with accel scale estimation, ex…
LorenzMeier Apr 19, 2014
479fddf
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 19, 2014
fd34a84
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 20, 2014
46a796f
Added home position switch on GPS position - gives a more reliable ho…
LorenzMeier Apr 20, 2014
7cad27a
Changed home position set to depend on the commander home position sw…
LorenzMeier Apr 20, 2014
9c5dbee
Proper zero init of the filter
LorenzMeier Apr 20, 2014
b37d0f8
Safety checks, prepared to use GPS variance
LorenzMeier Apr 20, 2014
200bd8e
Merge branch 'ekf_params' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 20, 2014
906abbc
mavlink: Only write to TX buf if space is available. This is working …
LorenzMeier Apr 20, 2014
9cc2847
Merge branch 'usb_buf_hotfix' into ekf_params
LorenzMeier Apr 20, 2014
609d266
Merge branch 'sensor_err_handling' into ekf_params
LorenzMeier Apr 20, 2014
1e202a2
Updated estimator, not using optical flow for now until proven on the…
LorenzMeier Apr 20, 2014
14fb653
ekf_att_pos_estimator: Using right app name
LorenzMeier Apr 20, 2014
c085447
att_pos_estimator_ekf: Update filter to new filter API
LorenzMeier Apr 20, 2014
aa3aafb
Added debug macro for EKF. Fixed mag state handling which was only pa…
LorenzMeier Apr 21, 2014
595eb67
ekf_att_pos_estimator: Fixed mag initialization, now starts with init…
LorenzMeier Apr 21, 2014
0a89364
Merge branch 'ArmDisarm' of github.com:DonLakeFlyer/Firmware into ekf…
LorenzMeier Apr 21, 2014
8ae50a4
Changed home position set to depend on the commander home position sw…
LorenzMeier Apr 20, 2014
37b133e
Added home position switch on GPS position - gives a more reliable ho…
LorenzMeier Apr 20, 2014
706d080
Better / cleaner initialization of the attitude estimator
LorenzMeier Apr 21, 2014
db15e28
commander: Fix altitude initialisation, do not depend on global pos v…
LorenzMeier Apr 21, 2014
42e9c84
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 21, 2014
3a4874b
Merge branch 'sensors_loop' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 21, 2014
119dfc4
Merged home_fix
LorenzMeier Apr 21, 2014
904ada1
ekf: Put reset statements after variable zero operation to ensure val…
LorenzMeier Apr 22, 2014
39a0d4e
Better error handling / reporting in filter
LorenzMeier Apr 22, 2014
125f0b2
Added trap to filter to catch NaN handling
LorenzMeier Apr 22, 2014
5b72096
Revert "HIL: Increased MAVLink link wait time based on previous exper…
LorenzMeier Apr 22, 2014
af56e65
Merge branch 'master' into ekf_params
LorenzMeier Apr 22, 2014
2ecaab9
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 22, 2014
bd63769
Removed verbose print
LorenzMeier Apr 22, 2014
1e80e62
ekf: Better variable zeroing
LorenzMeier Apr 22, 2014
4585df1
Robustified filter init / sequencing
LorenzMeier Apr 22, 2014
a30411e
Fixed printing in attitude control
LorenzMeier Apr 22, 2014
22d3bcd
Merged mpc_rc into ekf_params
LorenzMeier Apr 26, 2014
d4785d4
Use INAV as default to not break existing setups
LorenzMeier Apr 26, 2014
ad1be76
Fix warnings, use more efficient atan2f where it can be safely used
LorenzMeier Apr 26, 2014
5ad3ff9
Merged master into ekf_params
LorenzMeier Apr 26, 2014
9358eb2
Fixed string formatting error
LorenzMeier Apr 26, 2014
0d50b3e
Fix struct inits
LorenzMeier Apr 26, 2014
2d978be
Compile fixes
LorenzMeier Apr 26, 2014
18a932f
Better fake / simulation values
LorenzMeier Apr 26, 2014
6612cda
Let commander be less pedantic about positioning data
LorenzMeier Apr 26, 2014
9254307
Reworked how we deal with altitudes
LorenzMeier Apr 26, 2014
6ab878c
Emit the local position against the GPS reference - this means it can…
LorenzMeier Apr 26, 2014
f7065dc
Merged master into ekf_params
LorenzMeier Apr 27, 2014
0745334
Reset init flags as well
LorenzMeier Apr 28, 2014
df8fb7d
Merge branch 'ekf_params' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 28, 2014
2c37ec1
Merge branch 'autodeclination' into ekf_params
LorenzMeier Apr 28, 2014
90569d2
Added support for automatic mag declination setup
LorenzMeier Apr 28, 2014
f78005b
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 28, 2014
11a1053
ekf_att_pos_estimator: local position reference fixed
DrTon Apr 28, 2014
86d9fb5
Merge branch 'autodeclination' into ekf_params
LorenzMeier Apr 28, 2014
7c88fbf
Merge branch 'ekf_params' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 28, 2014
848c1c2
ekf: More complete re-initialization
LorenzMeier Apr 29, 2014
81525f6
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 30, 2014
d54f997
Fixed typos in declination table lookup
LorenzMeier Apr 30, 2014
e2af771
ekf: Cleanup init
LorenzMeier Apr 30, 2014
be1f39e
ekf Print declination on init
LorenzMeier Apr 30, 2014
c1b02ae
Merge branch 'autodeclination' into ekf_params
LorenzMeier Apr 30, 2014
918c879
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier Apr 30, 2014
7a4049b
Fix use of declination in estimator, remove bogus measurement value r…
LorenzMeier Apr 30, 2014
6cb96d0
EKF: Introduce proper check flags for sensor init states
LorenzMeier Apr 30, 2014
319ce3d
Minor cleanups in EKF estimator
LorenzMeier May 7, 2014
6a6feaf
Merged master
LorenzMeier May 7, 2014
21edf72
Do not send a critical message when switching to dynamic state
LorenzMeier May 7, 2014
2393715
Fixed re-initialization of estimator, re-initializes in air now relia…
LorenzMeier May 7, 2014
3e3a64f
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier May 9, 2014
da67b2b
Disable time compensation for further testing
LorenzMeier May 10, 2014
dc19f16
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier May 11, 2014
e098591
Addressed linter concerns
LorenzMeier May 11, 2014
5f392c8
More debug in filter
LorenzMeier May 11, 2014
d3a9aae
Merge branch 'master' of github.com:PX4/Firmware into ekf_params
LorenzMeier May 11, 2014
7ec8fe8
Experimental init delay
LorenzMeier May 11, 2014
5581802
ekf: Move dt inside class
LorenzMeier May 11, 2014
eeba000
stupid fix
LorenzMeier May 11, 2014
077de5e
Clean implementation of filter startup delay implementation
LorenzMeier May 11, 2014
1b3007a
Re-enabled time compensation
LorenzMeier May 11, 2014
f975f98
ekf: less console spam
LorenzMeier May 11, 2014
6906dc4
Minor improvements to estimator
LorenzMeier May 12, 2014
b8aae38
Merge branch 'ekf_params' of github.com:PX4/Firmware into ekf_params
LorenzMeier May 13, 2014
ec409a1
EKF / Paul Riseborough: Added guards for mag and airspeed innovations
LorenzMeier May 13, 2014
c04064f
sdlog2: Log minimalistic GPS SNR for first 16 satellites
LorenzMeier May 13, 2014
c9162f4
sdlog2: Remove an unreachable comparison
LorenzMeier May 13, 2014
e5508a1
Add Gumstix AeroCore device
ashcharles May 13, 2014
3b72e31
[l3gd20] Add support for L3G4200D chip
ashcharles May 13, 2014
9db966e
[gps] Conditionally set default GPS port
ashcharles May 13, 2014
7d0850a
[l3gd20] Style fixes for l3g4200d integration
ashcharles May 13, 2014
2d29c5b
[aerocore] Remove commented code for GPIO2
ashcharles May 13, 2014
b60964e
Multirotor mixer: more careful limiting
DrTon May 14, 2014
ae1faa6
MC mixer input limiting implemented.
DrTon May 14, 2014
42a7d80
mc_att_control: limit max yaw setpoint offset
DrTon May 14, 2014
cbc559b
[l3gd20] Make gyro orientation board-overridable
ashcharles May 14, 2014
8e43db7
mc_att_control: yaw offset limiting bug fixed
DrTon May 15, 2014
7ef3c24
Merge branch 'master' into yaw_offset_limit
DrTon May 15, 2014
899998e
px4io driver: Use modern-days syntax to start task
LorenzMeier May 15, 2014
97e6090
Merge pull request #937 from gumstix/aerocore
LorenzMeier May 15, 2014
ba51ab2
Merge branch 'ekf_params' of github.com:PX4/Firmware
LorenzMeier May 15, 2014
b9b84b0
Multirotor mixer: limit yaw first, then roll/pitch
DrTon May 15, 2014
a4c4080
Fixed alt ref init
LorenzMeier May 15, 2014
bc3ca8d
Multirotor mixer: yaw limiting bug fixed
DrTon May 15, 2014
c72ec3f
Merge pull request #958 from PX4/yaw_offset_limit
LorenzMeier May 15, 2014
8d1df9b
Merge branch 'master' into mc_mixer_fix
DrTon May 15, 2014
19ebe07
Fix aerocore config
LorenzMeier May 15, 2014
8662a06
Merge branch 'master' of github.com:PX4/Firmware into gps_logging
LorenzMeier May 15, 2014
d9a7e52
Multirotor mixer: idle_speed (aka deadband) fixed
DrTon May 15, 2014
ac4b68e
Merge pull request #936 from PX4/gps_logging
LorenzMeier May 15, 2014
f892a72
Merge pull request #956 from PX4/task_spawn_cmd_io
LorenzMeier May 16, 2014
b903fc1
px4io: Improve the documentation of the protocol header, NO FUNCTIONA…
LorenzMeier May 16, 2014
4fe0027
px4io driver: Only try to upload if we have a non-zero failsafe throt…
LorenzMeier May 16, 2014
5ca9663
px4io firmware: Actually accept failsafe values, check their range. A…
LorenzMeier May 16, 2014
1b49100
Minor cleanups on handling, make wrong reg accesses non-fatal for the…
LorenzMeier May 16, 2014
f66cd1a
frsky telem: reduce stack, fix missing header
LorenzMeier May 16, 2014
842819a
Use smaller logging buffer
LorenzMeier May 16, 2014
0a6861e
FMUv1: Reduce user main stack slightly, still 2.5K buffer between act…
LorenzMeier May 16, 2014
8630d82
gps driver: Use correct spawn command, use a smaller start tool size
LorenzMeier May 16, 2014
9d2bfb5
flow example: Use smaller stack and correct start logic
LorenzMeier May 16, 2014
cccd3e1
mavlink app: Reduce stack sizes minimally after further inspection
LorenzMeier May 16, 2014
834a230
inav: Reduce stack size of start tool
LorenzMeier May 16, 2014
30123c8
inav: Fix scheduling type, we want ALL processes to stick to DEFAULT
LorenzMeier May 16, 2014
ea99fd8
nshterm: Reduce stack size further after more thorough inspection
LorenzMeier May 16, 2014
a63fc9b
Merge pull request #964 from PX4/px4io_fixes
LorenzMeier May 16, 2014
a72015c
Merge pull request #965 from PX4/stack_fixes
LorenzMeier May 16, 2014
68b1cde
Merge branch 'master' into mc_mixer_fix
DrTon May 17, 2014
f52edc4
ekf_att_pos_estimator: fixed files names and perf counters names
DrTon May 17, 2014
98fcec2
ekf_att_pos_estimator: module.mk fixed
DrTon May 17, 2014
1d6bd3b
Merge pull request #971 from PX4/ekf_cleanup
LorenzMeier May 17, 2014
32ae2dd
commander: missed 'break' in 'switch' added
DrTon May 17, 2014
98f05ea
Merge pull request #942 from PX4/mc_mixer_fix
LorenzMeier May 17, 2014
ce62f07
Fix EPH / EPV conversion for MediaTek units
LorenzMeier May 19, 2014
f063054
MTK: Bail out correctly
LorenzMeier May 19, 2014
b250e28
Merge pull request #978 from PX4/mtk_fix
thomasgubler May 19, 2014
b129285
Merge branch 'master' into acro2
DrTon May 19, 2014
d8ef397
mc_att_control: reset yaw setpoint after ACRO
DrTon May 20, 2014
559bfbb
commander: allow disarm in ACRO mode
DrTon May 20, 2014
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
37 changes: 32 additions & 5 deletions src/modules/commander/commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -621,9 +621,10 @@ int commander_thread_main(int argc, char *argv[])

char *main_states_str[MAIN_STATE_MAX];
main_states_str[0] = "MANUAL";
main_states_str[1] = "SEATBELT";
main_states_str[2] = "EASY";
main_states_str[3] = "AUTO";
main_states_str[1] = "ACRO";
main_states_str[2] = "SEATBELT";
main_states_str[3] = "EASY";
main_states_str[4] = "AUTO";

char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[0] = "INIT";
Expand Down Expand Up @@ -1131,7 +1132,7 @@ int commander_thread_main(int argc, char *argv[])
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
(status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
(status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {

if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
Expand Down Expand Up @@ -1522,6 +1523,17 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
} else {
status->mission_switch = MISSION_SWITCH_MISSION;
}

/* acro switch */
if (!isfinite(sp_man->acro_switch)) {
status->acro_switch = ACRO_SWITCH_NONE;

} else if (sp_man->acro_switch > STICK_ON_OFF_LIMIT) {
status->acro_switch = ACRO_SWITCH_ACRO;

} else {
status->acro_switch = ACRO_SWITCH_NORMAL;
}
}

transition_result_t
Expand All @@ -1532,7 +1544,11 @@ set_main_state_rc(struct vehicle_status_s *status)

switch (status->mode_switch) {
case MODE_SWITCH_MANUAL:
res = main_state_transition(status, MAIN_STATE_MANUAL);
if (status->acro_switch == ACRO_SWITCH_ACRO) {
res = main_state_transition(status, MAIN_STATE_ACRO);
} else {
res = main_state_transition(status, MAIN_STATE_MANUAL);
}
// TRANSITION_DENIED is not possible here
break;

Expand Down Expand Up @@ -1613,6 +1629,17 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;

case MAIN_STATE_ACRO:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = false;
control_mode.flag_control_altitude_enabled = false;
control_mode.flag_control_climb_rate_enabled = false;
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;

case MAIN_STATE_SEATBELT:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
Expand Down
4 changes: 4 additions & 0 deletions src/modules/commander/state_machine_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,10 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;

case MAIN_STATE_ACRO:
ret = TRANSITION_CHANGED;
break;

case MAIN_STATE_SEATBELT:

/* need at minimum altitude estimate */
Expand Down
106 changes: 79 additions & 27 deletions src/modules/mc_att_control/mc_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,12 @@ class MulticopterAttitudeControl
param_t yaw_rate_i;
param_t yaw_rate_d;
param_t yaw_ff;
param_t roll_scale_acro;
param_t pitch_scale_acro;
param_t yaw_scale_acro;

param_t rc_scale_roll;
param_t rc_scale_pitch;
param_t rc_scale_yaw;
} _params_handles; /**< handles for interesting parameters */

Expand All @@ -171,8 +176,9 @@ class MulticopterAttitudeControl
math::Vector<3> rate_i; /**< I gain for angular rate error */
math::Vector<3> rate_d; /**< D gain for angular rate error */
float yaw_ff; /**< yaw control feed-forward */
math::Vector<3> scale_acro; /**< scale for ACRO mode */

float rc_scale_yaw;
math::Vector<3> rc_scale; /**< scale for MANUAL mode */
} _params;

/**
Expand Down Expand Up @@ -275,6 +281,8 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params.rate_p.zero();
_params.rate_i.zero();
_params.rate_d.zero();
_params.scale_acro.zero();
_params.rc_scale.zero();

_R_sp.identity();
_R.identity();
Expand All @@ -286,21 +294,26 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :

I.identity();

_params_handles.roll_p = param_find("MC_ROLL_P");
_params_handles.roll_rate_p = param_find("MC_ROLLRATE_P");
_params_handles.roll_rate_i = param_find("MC_ROLLRATE_I");
_params_handles.roll_rate_d = param_find("MC_ROLLRATE_D");
_params_handles.pitch_p = param_find("MC_PITCH_P");
_params_handles.pitch_rate_p = param_find("MC_PITCHRATE_P");
_params_handles.pitch_rate_i = param_find("MC_PITCHRATE_I");
_params_handles.pitch_rate_d = param_find("MC_PITCHRATE_D");
_params_handles.yaw_p = param_find("MC_YAW_P");
_params_handles.yaw_rate_p = param_find("MC_YAWRATE_P");
_params_handles.yaw_rate_i = param_find("MC_YAWRATE_I");
_params_handles.yaw_rate_d = param_find("MC_YAWRATE_D");
_params_handles.yaw_ff = param_find("MC_YAW_FF");

_params_handles.rc_scale_yaw = param_find("RC_SCALE_YAW");
_params_handles.roll_p = param_find("MC_ROLL_P");
_params_handles.roll_rate_p = param_find("MC_ROLLRATE_P");
_params_handles.roll_rate_i = param_find("MC_ROLLRATE_I");
_params_handles.roll_rate_d = param_find("MC_ROLLRATE_D");
_params_handles.pitch_p = param_find("MC_PITCH_P");
_params_handles.pitch_rate_p = param_find("MC_PITCHRATE_P");
_params_handles.pitch_rate_i = param_find("MC_PITCHRATE_I");
_params_handles.pitch_rate_d = param_find("MC_PITCHRATE_D");
_params_handles.yaw_p = param_find("MC_YAW_P");
_params_handles.yaw_rate_p = param_find("MC_YAWRATE_P");
_params_handles.yaw_rate_i = param_find("MC_YAWRATE_I");
_params_handles.yaw_rate_d = param_find("MC_YAWRATE_D");
_params_handles.yaw_ff = param_find("MC_YAW_FF");
_params_handles.roll_scale_acro = param_find("MC_ROLL_S_ACRO");
_params_handles.pitch_scale_acro = param_find("MC_PITCH_S_ACRO");
_params_handles.yaw_scale_acro = param_find("MC_YAW_S_ACRO");

_params_handles.rc_scale_roll = param_find("RC_SCALE_ROLL");
_params_handles.rc_scale_pitch = param_find("RC_SCALE_PITCH");
_params_handles.rc_scale_yaw = param_find("RC_SCALE_YAW");

/* fetch initial parameter values */
parameters_update();
Expand Down Expand Up @@ -344,6 +357,10 @@ MulticopterAttitudeControl::parameters_update()
_params.rate_i(0) = v;
param_get(_params_handles.roll_rate_d, &v);
_params.rate_d(0) = v;
param_get(_params_handles.roll_scale_acro, &v);
_params.scale_acro(0) = v;
param_get(_params_handles.rc_scale_roll, &v);
_params.rc_scale(0) = v;

/* pitch */
param_get(_params_handles.pitch_p, &v);
Expand All @@ -354,6 +371,10 @@ MulticopterAttitudeControl::parameters_update()
_params.rate_i(1) = v;
param_get(_params_handles.pitch_rate_d, &v);
_params.rate_d(1) = v;
param_get(_params_handles.pitch_scale_acro, &v);
_params.scale_acro(1) = v;
param_get(_params_handles.rc_scale_pitch, &v);
_params.rc_scale(1) = v;

/* yaw */
param_get(_params_handles.yaw_p, &v);
Expand All @@ -364,10 +385,11 @@ MulticopterAttitudeControl::parameters_update()
_params.rate_i(2) = v;
param_get(_params_handles.yaw_rate_d, &v);
_params.rate_d(2) = v;

param_get(_params_handles.yaw_ff, &_params.yaw_ff);

param_get(_params_handles.rc_scale_yaw, &_params.rc_scale_yaw);
param_get(_params_handles.yaw_scale_acro, &v);
_params.scale_acro(2) = v;
param_get(_params_handles.rc_scale_yaw, &v);
_params.rc_scale(2) = v;

return OK;
}
Expand Down Expand Up @@ -463,6 +485,7 @@ MulticopterAttitudeControl::control_attitude(float dt)

if (_v_control_mode.flag_control_manual_enabled) {
/* manual input, set or modify attitude setpoint */
vehicle_manual_poll();

if (_v_control_mode.flag_control_velocity_enabled || _v_control_mode.flag_control_climb_rate_enabled) {
/* in assisted modes poll 'vehicle_attitude_setpoint' topic and modify it */
Expand All @@ -488,11 +511,11 @@ MulticopterAttitudeControl::control_attitude(float dt)
// reset_yaw_sp = true;
//}
} else {
float yaw_dz_scaled = YAW_DEADZONE * _params.rc_scale_yaw;
float yaw_dz_scaled = YAW_DEADZONE * _params.rc_scale(2);

if (_params.rc_scale_yaw > 0.001f && fabs(_manual_control_sp.yaw) > yaw_dz_scaled) {
if (_params.rc_scale(2) > 0.001f && fabs(_manual_control_sp.yaw) > yaw_dz_scaled) {
/* move yaw setpoint */
yaw_sp_move_rate = _manual_control_sp.yaw / _params.rc_scale_yaw;
yaw_sp_move_rate = _manual_control_sp.yaw / _params.rc_scale(2);

if (_manual_control_sp.yaw > 0.0f) {
yaw_sp_move_rate -= YAW_DEADZONE;
Expand All @@ -501,7 +524,7 @@ MulticopterAttitudeControl::control_attitude(float dt)
yaw_sp_move_rate += YAW_DEADZONE;
}

yaw_sp_move_rate *= _params.rc_scale_yaw;
yaw_sp_move_rate *= _params.rc_scale(2);
_v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + yaw_sp_move_rate * dt);
_v_att_sp.R_valid = false;
publish_att_sp = true;
Expand Down Expand Up @@ -747,7 +770,6 @@ MulticopterAttitudeControl::task_main()
parameter_update_poll();
vehicle_control_mode_poll();
arming_status_poll();
vehicle_manual_poll();

if (_v_control_mode.flag_control_attitude_enabled) {
control_attitude(dt);
Expand All @@ -768,9 +790,39 @@ MulticopterAttitudeControl::task_main()

} else {
/* attitude controller disabled */
// TODO poll 'attitude_rates_setpoint' topic
_rates_sp.zero();
_thrust_sp = 0.0f;
if (_v_control_mode.flag_control_manual_enabled) {
/* manual rates control, ACRO mode */
vehicle_manual_poll();

_rates_sp(0) = _manual_control_sp.roll;
_rates_sp(1) = _manual_control_sp.pitch;
_rates_sp(2) = _manual_control_sp.yaw;

/* rescale controls for ACRO mode */
_rates_sp = _rates_sp.edivide(_params.rc_scale).emult(_params.scale_acro);
_thrust_sp = _manual_control_sp.throttle;

_reset_yaw_sp = true;

/* publish attitude rates setpoint */
_v_rates_sp.roll = _rates_sp(0);
_v_rates_sp.pitch = _rates_sp(1);
_v_rates_sp.yaw = _rates_sp(2);
_v_rates_sp.thrust = _thrust_sp;
_v_rates_sp.timestamp = hrt_absolute_time();

if (_v_rates_sp_pub > 0) {
orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp);

} else {
_v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp);
}

} else {
// TODO poll 'attitude_rates_setpoint' topic
_rates_sp.zero();
_thrust_sp = 0.0f;
}
}

if (_v_control_mode.flag_control_rates_enabled) {
Expand Down
3 changes: 3 additions & 0 deletions src/modules/mc_att_control/mc_att_control_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -54,3 +54,6 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f);
PARAM_DEFINE_FLOAT(MC_ROLL_S_ACRO, 5.0f);
PARAM_DEFINE_FLOAT(MC_PITCH_S_ACRO, 5.0f);
PARAM_DEFINE_FLOAT(MC_YAW_S_ACRO, 3.0f);
1 change: 1 addition & 0 deletions src/modules/sensors/sensor_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -449,6 +449,7 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);

//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);

Expand Down
14 changes: 14 additions & 0 deletions src/modules/sensors/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,7 @@ class Sensors
int rc_map_return_sw;
int rc_map_assisted_sw;
int rc_map_mission_sw;
int rc_map_acro_sw;

// int rc_map_offboard_ctrl_mode_sw;

Expand Down Expand Up @@ -295,6 +296,7 @@ class Sensors
param_t rc_map_return_sw;
param_t rc_map_assisted_sw;
param_t rc_map_mission_sw;
param_t rc_map_acro_sw;

// param_t rc_map_offboard_ctrl_mode_sw;

Expand Down Expand Up @@ -514,6 +516,7 @@ Sensors::Sensors() :
/* optional mode switches, not mapped per default */
_parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
_parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
_parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");

// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");

Expand Down Expand Up @@ -670,6 +673,10 @@ Sensors::parameters_update()
warnx(paramerr);
}

if (param_get(_parameter_handles.rc_map_acro_sw, &(_parameters.rc_map_acro_sw)) != OK) {
warnx("Failed getting acro sw chan index");
Copy link
Contributor

Choose a reason for hiding this comment

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

Should be

warnx(paramerr);

}

if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx(paramerr);
}
Expand Down Expand Up @@ -701,6 +708,7 @@ Sensors::parameters_update()
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
_rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
_rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
_rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;

_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;

Expand Down Expand Up @@ -1291,6 +1299,7 @@ Sensors::rc_poll()
manual_control.return_switch = NAN;
manual_control.assisted_switch = NAN;
manual_control.mission_switch = NAN;
manual_control.acro_switch = NAN;
// manual_control.auto_offboard_input_switch = NAN;

manual_control.flaps = NAN;
Expand Down Expand Up @@ -1429,6 +1438,11 @@ Sensors::rc_poll()
manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}

/* acro switch input */
if (_rc.function[ACRO] >= 0) {
manual_control.acro_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ACRO]].scaled);
}

/* return switch input */
if (_rc.function[RETURN] >= 0) {
manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
Expand Down
1 change: 1 addition & 0 deletions src/modules/uORB/topics/manual_control_setpoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ struct manual_control_setpoint_s {
float return_switch; /**< land 2 position switch (mandatory): land, no effect */
float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
float acro_switch; /**< acro 2 position switch (optional): normal, acro */

/**
* Any of the channels below may not be available and be set to NaN
Expand Down
11 changes: 6 additions & 5 deletions src/modules/uORB/topics/rc_channels.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,11 +68,12 @@ enum RC_CHANNELS_FUNCTION
ASSISTED = 6,
MISSION = 7,
OFFBOARD_MODE = 8,
FLAPS = 9,
AUX_1 = 10,
AUX_2 = 11,
AUX_3 = 12,
AUX_4 = 13,
ACRO = 9,
FLAPS = 10,
AUX_1 = 11,
AUX_2 = 12,
AUX_3 = 13,
AUX_4 = 14,
AUX_5 = 14,
Copy link
Contributor

Choose a reason for hiding this comment

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

AUX_4 and AUX_5 are both 14 now? Doesn't sound right...

RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
Expand Down
Loading