Skip to content

Commit

Permalink
Added RC reverse and deadzones
Browse files Browse the repository at this point in the history
  • Loading branch information
pryre committed May 17, 2018
1 parent 76b94cd commit 4161458
Show file tree
Hide file tree
Showing 7 changed files with 335 additions and 23 deletions.
9 changes: 6 additions & 3 deletions include/sensors.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#define SENSOR_RC_CAL_MID 1
#define SENSOR_RC_CAL_MAX 2

#define SENSOR_RC_MIDSTICK 1500

//XXX: Defined in MAV_CMD_PREFLIGHT_CALIBRATION
//Param1
#define SENSOR_CAL_CMD_GYRO 1
Expand Down Expand Up @@ -183,7 +185,7 @@ typedef enum {
SENSOR_CAL_GYRO = 1,
SENSOR_CAL_MAG = 2,
SENSOR_CAL_BARO = 4,
SENSOR_CAL_RC = 8, //Calibrate ESCs?
SENSOR_CAL_RC = 8,
SENSOR_CAL_ACCEL = 16,
SENSOR_CAL_INTER = 32, //TODO: Implement this
SENSOR_CAL_ALL = 128
Expand All @@ -192,15 +194,16 @@ typedef enum {
typedef enum {
SENSOR_CAL_RC_RANGE_INIT = 0,
SENSOR_CAL_RC_RANGE_MIDDOWN,
SENSOR_CAL_RC_RANGE_CORNERS,
SENSOR_CAL_RC_RANGE_EXTREMES,
SENSOR_CAL_RC_RANGE_DONE
} sensor_calibration_rc_range_t;

typedef struct {
bool waiting;
sensor_calibration_rc_range_t step;
uint16_t rc_ranges[8][3];
bool rc_rev[8]; //TODO: reverses, RC mode type
uint16_t rc_ranges[8][4];
bool rc_rev[8];
} sensor_calibration_rc_range_data_t;

typedef struct {
Expand Down
16 changes: 16 additions & 0 deletions lib/param_generator/PARAMS.md
Original file line number Diff line number Diff line change
Expand Up @@ -121,27 +121,43 @@ COM_RC_ARM_HYST | uint | Time threshold to activate RC arming | 1000000 | us | s
RC1_MIN | uint | RC minimum value for channel 1 calibration | 1000 | channel | scalar | False
RC1_TRIM | uint | RC median value for channel 1 calibration | 1500 | channel | scalar | False
RC1_MAX | uint | RC max value for channel 1 calibration | 2000 | channel | scalar | False
RC1_REV | uint | RC reverse reading channel 1 calibration | 0 | 0 / 1 | boolean | False
RC1_DZ | float | RC deadzone for channel 1 | 0.02 | | scalar | False
RC2_MIN | uint | RC minimum value for channel 2 calibration | 1000 | channel | scalar | False
RC2_TRIM | uint | RC median value for channel 2 calibration | 1500 | channel | scalar | False
RC2_MAX | uint | RC max value for channel 2 calibration | 2000 | channel | scalar | False
RC2_REV | uint | RC reverse reading channel 2 calibration | 0 | 0 / 1 | boolean | False
RC2_DZ | float | RC deadzone for channel 2 | 0.02 | | scalar | False
RC3_MIN | uint | RC minimum value for channel 3 calibration | 1000 | channel | scalar | False
RC3_TRIM | uint | RC median value for channel 3 calibration | 1500 | channel | scalar | False
RC3_MAX | uint | RC max value for channel 3 calibration | 2000 | channel | scalar | False
RC3_REV | uint | RC reverse reading channel 3 calibration | 0 | 0 / 1 | boolean | False
RC3_DZ | float | RC deadzone for channel 3 | 0.02 | | scalar | False
RC4_MIN | uint | RC minimum value for channel 4 calibration | 1000 | channel | scalar | False
RC4_TRIM | uint | RC median value for channel 4 calibration | 1500 | channel | scalar | False
RC4_MAX | uint | RC max value for channel 4 calibration | 2000 | channel | scalar | False
RC4_REV | uint | RC reverse reading channel 4 calibration | 0 | 0 / 1 | boolean | False
RC4_DZ | float | RC deadzone for channel 4 | 0.02 | | scalar | False
RC5_MIN | uint | RC minimum value for channel 5 calibration | 1000 | channel | scalar | False
RC5_TRIM | uint | RC median value for channel 5 calibration | 1500 | channel | scalar | False
RC5_MAX | uint | RC max value for channel 5 calibration | 2000 | channel | scalar | False
RC5_REV | uint | RC reverse reading channel 5 calibration | 0 | 0 / 1 | boolean | False
RC5_DZ | float | RC deadzone for channel 5 | 0.02 | | scalar | False
RC6_MIN | uint | RC minimum value for channel 6 calibration | 1000 | channel | scalar | False
RC6_TRIM | uint | RC median value for channel 6 calibration | 1500 | channel | scalar | False
RC6_MAX | uint | RC max value for channel 6 calibration | 2000 | channel | scalar | False
RC6_REV | uint | RC reverse reading channel 6 calibration | 0 | 0 / 1 | boolean | False
RC6_DZ | float | RC deadzone for channel 6 | 0.02 | | scalar | False
RC7_MIN | uint | RC minimum value for channel 7 calibration | 1000 | channel | scalar | False
RC7_TRIM | uint | RC median value for channel 7 calibration | 1500 | channel | scalar | False
RC7_MAX | uint | RC max value for channel 7 calibration | 2000 | channel | scalar | False
RC7_REV | uint | RC reverse reading channel 7 calibration | 0 | 0 / 1 | boolean | False
RC7_DZ | float | RC deadzone for channel 7 | 0.02 | | scalar | False
RC8_MIN | uint | RC minimum value for channel 8 calibration | 1000 | channel | scalar | False
RC8_TRIM | uint | RC median value for channel 8 calibration | 1500 | channel | scalar | False
RC8_MAX | uint | RC max value for channel 8 calibration | 2000 | channel | scalar | False
RC8_REV | uint | RC reverse reading channel 8 calibration | 0 | 0 / 1 | boolean | False
RC8_DZ | float | RC deadzone for channel 8 | 0.02 | | scalar | False
DO_ESC_CAL | uint | When set to true, a motor calibration will be performed on the next boot (False:0,True:1) | 0 | 0 / 1 | boolean | True
FAILSAFE_THRTL | float | Throttle percentage output when in failsafe mode | 0.25 | | scalar | False
TIMEOUT_THRTL | uint | Throttle timeout in to prevent accidentally leaving armed | 10000000 | us | scalar | False
Expand Down
56 changes: 56 additions & 0 deletions lib/param_generator/param_gen.c
Original file line number Diff line number Diff line change
Expand Up @@ -127,27 +127,43 @@ void set_param_defaults(void) {
init_param_uint(PARAM_RC1_MIN, 1000);
init_param_uint(PARAM_RC1_MID, 1500);
init_param_uint(PARAM_RC1_MAX, 2000);
init_param_uint(PARAM_RC1_REV, 0);
init_param_fix16(PARAM_RC1_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC2_MIN, 1000);
init_param_uint(PARAM_RC2_MID, 1500);
init_param_uint(PARAM_RC2_MAX, 2000);
init_param_uint(PARAM_RC2_REV, 0);
init_param_fix16(PARAM_RC2_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC3_MIN, 1000);
init_param_uint(PARAM_RC3_MID, 1500);
init_param_uint(PARAM_RC3_MAX, 2000);
init_param_uint(PARAM_RC3_REV, 0);
init_param_fix16(PARAM_RC3_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC4_MIN, 1000);
init_param_uint(PARAM_RC4_MID, 1500);
init_param_uint(PARAM_RC4_MAX, 2000);
init_param_uint(PARAM_RC4_REV, 0);
init_param_fix16(PARAM_RC4_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC5_MIN, 1000);
init_param_uint(PARAM_RC5_MID, 1500);
init_param_uint(PARAM_RC5_MAX, 2000);
init_param_uint(PARAM_RC5_REV, 0);
init_param_fix16(PARAM_RC5_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC6_MIN, 1000);
init_param_uint(PARAM_RC6_MID, 1500);
init_param_uint(PARAM_RC6_MAX, 2000);
init_param_uint(PARAM_RC6_REV, 0);
init_param_fix16(PARAM_RC6_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC7_MIN, 1000);
init_param_uint(PARAM_RC7_MID, 1500);
init_param_uint(PARAM_RC7_MAX, 2000);
init_param_uint(PARAM_RC7_REV, 0);
init_param_fix16(PARAM_RC7_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_RC8_MIN, 1000);
init_param_uint(PARAM_RC8_MID, 1500);
init_param_uint(PARAM_RC8_MAX, 2000);
init_param_uint(PARAM_RC8_REV, 0);
init_param_fix16(PARAM_RC8_DZ, fix16_from_float(0.02f));
init_param_uint(PARAM_DO_ESC_CAL, 0);
init_param_fix16(PARAM_FAILSAFE_THROTTLE, fix16_from_float(0.25f));
init_param_uint(PARAM_THROTTLE_TIMEOUT, 10000000);
Expand Down Expand Up @@ -276,27 +292,43 @@ const char _param_names[PARAMS_COUNT][MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
"RC1_MIN",
"RC1_TRIM",
"RC1_MAX",
"RC1_REV",
"RC1_DZ",
"RC2_MIN",
"RC2_TRIM",
"RC2_MAX",
"RC2_REV",
"RC2_DZ",
"RC3_MIN",
"RC3_TRIM",
"RC3_MAX",
"RC3_REV",
"RC3_DZ",
"RC4_MIN",
"RC4_TRIM",
"RC4_MAX",
"RC4_REV",
"RC4_DZ",
"RC5_MIN",
"RC5_TRIM",
"RC5_MAX",
"RC5_REV",
"RC5_DZ",
"RC6_MIN",
"RC6_TRIM",
"RC6_MAX",
"RC6_REV",
"RC6_DZ",
"RC7_MIN",
"RC7_TRIM",
"RC7_MAX",
"RC7_REV",
"RC7_DZ",
"RC8_MIN",
"RC8_TRIM",
"RC8_MAX",
"RC8_REV",
"RC8_DZ",
"DO_ESC_CAL",
"FAILSAFE_THRTL",
"TIMEOUT_THRTL",
Expand Down Expand Up @@ -390,6 +422,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC1_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC1_REV:
sensors_update_rc_cal();
break;
case PARAM_RC2_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -399,6 +434,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC2_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC2_REV:
sensors_update_rc_cal();
break;
case PARAM_RC3_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -408,6 +446,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC3_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC3_REV:
sensors_update_rc_cal();
break;
case PARAM_RC4_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -417,6 +458,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC4_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC4_REV:
sensors_update_rc_cal();
break;
case PARAM_RC5_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -426,6 +470,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC5_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC5_REV:
sensors_update_rc_cal();
break;
case PARAM_RC6_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -435,6 +482,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC6_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC6_REV:
sensors_update_rc_cal();
break;
case PARAM_RC7_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -444,6 +494,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC7_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC7_REV:
sensors_update_rc_cal();
break;
case PARAM_RC8_MIN:
sensors_update_rc_cal();
break;
Expand All @@ -453,6 +506,9 @@ void param_change_callback(param_id_t id) {
case PARAM_RC8_MAX:
sensors_update_rc_cal();
break;
case PARAM_RC8_REV:
sensors_update_rc_cal();
break;
case PARAM_MIXER:
write_params();
break;
Expand Down
16 changes: 16 additions & 0 deletions lib/param_generator/param_gen.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,27 +122,43 @@ typedef enum {
PARAM_RC1_MIN,
PARAM_RC1_MID,
PARAM_RC1_MAX,
PARAM_RC1_REV,
PARAM_RC1_DZ,
PARAM_RC2_MIN,
PARAM_RC2_MID,
PARAM_RC2_MAX,
PARAM_RC2_REV,
PARAM_RC2_DZ,
PARAM_RC3_MIN,
PARAM_RC3_MID,
PARAM_RC3_MAX,
PARAM_RC3_REV,
PARAM_RC3_DZ,
PARAM_RC4_MIN,
PARAM_RC4_MID,
PARAM_RC4_MAX,
PARAM_RC4_REV,
PARAM_RC4_DZ,
PARAM_RC5_MIN,
PARAM_RC5_MID,
PARAM_RC5_MAX,
PARAM_RC5_REV,
PARAM_RC5_DZ,
PARAM_RC6_MIN,
PARAM_RC6_MID,
PARAM_RC6_MAX,
PARAM_RC6_REV,
PARAM_RC6_DZ,
PARAM_RC7_MIN,
PARAM_RC7_MID,
PARAM_RC7_MAX,
PARAM_RC7_REV,
PARAM_RC7_DZ,
PARAM_RC8_MIN,
PARAM_RC8_MID,
PARAM_RC8_MAX,
PARAM_RC8_REV,
PARAM_RC8_DZ,
PARAM_DO_ESC_CAL,
PARAM_FAILSAFE_THROTTLE,
PARAM_THROTTLE_TIMEOUT,
Expand Down
Loading

0 comments on commit 4161458

Please sign in to comment.