mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 11:59:58 +03:00
merged in mwii2.3 generic servo handler. completely untested.
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@434 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
37b73a057b
commit
9ebd82c5ef
7 changed files with 83 additions and 119 deletions
21
src/cli.c
21
src/cli.c
|
@ -150,28 +150,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "rssi_aux_channel", VAR_INT8, &mcfg.rssi_aux_channel, 0, 4 },
|
||||
{ "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8, &cfg.tri_unarmed_servo, 0, 1 },
|
||||
{ "tri_yaw_middle", VAR_UINT16, &cfg.tri_yaw_middle, 0, 2000 },
|
||||
{ "tri_yaw_min", VAR_UINT16, &cfg.tri_yaw_min, 0, 2000 },
|
||||
{ "tri_yaw_max", VAR_UINT16, &cfg.tri_yaw_max, 0, 2000 },
|
||||
{ "wing_left_min", VAR_UINT16, &cfg.wing_left_min, 0, 2000 },
|
||||
{ "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 },
|
||||
{ "wing_left_max", VAR_UINT16, &cfg.wing_left_max, 0, 2000 },
|
||||
{ "wing_right_min", VAR_UINT16, &cfg.wing_right_min, 0, 2000 },
|
||||
{ "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 },
|
||||
{ "wing_right_max", VAR_UINT16, &cfg.wing_right_max, 0, 2000 },
|
||||
{ "pitch_direction_l", VAR_INT8, &cfg.pitch_direction_l, -1, 1 },
|
||||
{ "pitch_direction_r", VAR_INT8, &cfg.pitch_direction_r, -1, 1 },
|
||||
{ "roll_direction_l", VAR_INT8, &cfg.roll_direction_l, -1, 1 },
|
||||
{ "roll_direction_r", VAR_INT8, &cfg.roll_direction_r, -1, 1 },
|
||||
{ "gimbal_flags", VAR_UINT8, &cfg.gimbal_flags, 0, 255},
|
||||
{ "gimbal_pitch_gain", VAR_INT8, &cfg.gimbal_pitch_gain, -100, 100 },
|
||||
{ "gimbal_roll_gain", VAR_INT8, &cfg.gimbal_roll_gain, -100, 100 },
|
||||
{ "gimbal_pitch_min", VAR_UINT16, &cfg.gimbal_pitch_min, 100, 3000 },
|
||||
{ "gimbal_pitch_max", VAR_UINT16, &cfg.gimbal_pitch_max, 100, 3000 },
|
||||
{ "gimbal_pitch_mid", VAR_UINT16, &cfg.gimbal_pitch_mid, 100, 3000 },
|
||||
{ "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 },
|
||||
{ "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 },
|
||||
{ "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 },
|
||||
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 },
|
||||
{ "accxy_deadband", VAR_UINT8, &cfg.accxy_deadband, 0, 100 },
|
||||
{ "accz_deadband", VAR_UINT8, &cfg.accz_deadband, 0, 100 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue