Update CLI so that you can dump all, master or profile settings.
Cleanup '...' strings to reduce binary size. Change version information. With this change it's much more obvious what is and what is not included in a profile. Examples: dump dump profile dump master
This commit is contained in:
parent
81cf29be70
commit
8c3a869251
1
Makefile
1
Makefile
|
@ -355,6 +355,7 @@ CFLAGS = $(ARCH_FLAGS) \
|
|||
-DUSE_STDPERIPH_DRIVER \
|
||||
$(TARGET_FLAGS) \
|
||||
-D'__FORKNAME__="$(FORKNAME)"' \
|
||||
-D'__TARGET__="$(TARGET)"' \
|
||||
-save-temps=obj
|
||||
|
||||
|
||||
|
|
|
@ -154,198 +154,204 @@ const clicmd_t cmdTable[] = {
|
|||
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
|
||||
|
||||
typedef enum {
|
||||
VAR_UINT8,
|
||||
VAR_INT8,
|
||||
VAR_UINT16,
|
||||
VAR_INT16,
|
||||
VAR_UINT32,
|
||||
VAR_FLOAT
|
||||
} vartype_e;
|
||||
VAR_UINT8 = (1 << 0),
|
||||
VAR_INT8 = (1 << 1),
|
||||
VAR_UINT16 = (1 << 2),
|
||||
VAR_INT16 = (1 << 3),
|
||||
VAR_UINT32 = (1 << 4),
|
||||
VAR_FLOAT = (1 << 5),
|
||||
|
||||
MASTER_VALUE = (1 << 6),
|
||||
PROFILE_VALUE = (1 << 7)
|
||||
} cliValueFlag_e;
|
||||
|
||||
#define VALUE_TYPE_MASK (VAR_UINT8 | VAR_INT8 | VAR_UINT16 | VAR_INT16 | VAR_UINT32 | VAR_FLOAT)
|
||||
#define SECTION_MASK (MASTER_VALUE | PROFILE_VALUE)
|
||||
|
||||
typedef struct {
|
||||
const char *name;
|
||||
const uint8_t type; // vartype_e
|
||||
const uint8_t type; // cliValueFlag_e - specify one of each from VALUE_TYPE_MASK and SECTION_MASK
|
||||
void *ptr;
|
||||
const int32_t min;
|
||||
const int32_t max;
|
||||
} clivalue_t;
|
||||
|
||||
const clivalue_t valueTable[] = {
|
||||
{ "looptime", VAR_UINT16, &masterConfig.looptime, 0, 9000 },
|
||||
{ "emf_avoidance", VAR_UINT8, &masterConfig.emf_avoidance, 0, 1 },
|
||||
{ "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 9000 },
|
||||
{ "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 },
|
||||
|
||||
{ "mid_rc", VAR_UINT16, &masterConfig.rxConfig.midrc, 1200, 1700 },
|
||||
{ "min_check", VAR_UINT16, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "max_check", VAR_UINT16, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "rssi_channel", VAR_INT8, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
|
||||
{ "input_filtering_mode", VAR_INT8, &masterConfig.inputFilteringMode, 0, 1 },
|
||||
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, 1200, 1700 },
|
||||
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
|
||||
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE, &masterConfig.inputFilteringMode, 0, 1 },
|
||||
|
||||
{ "min_throttle", VAR_UINT16, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "max_throttle", VAR_UINT16, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "min_command", VAR_UINT16, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
||||
{ "3d_deadband_low", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME upper limit should match code in the mixer, 1500 currently
|
||||
{ "3d_deadband_high", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME lower limit should match code in the mixer, 1500 currently,
|
||||
{ "3d_neutral", VAR_UINT16, &masterConfig.flight3DConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "3d_deadband_throttle", VAR_UINT16, &masterConfig.flight3DConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME upper limit should match code in the mixer, 1500 currently
|
||||
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME lower limit should match code in the mixer, 1500 currently,
|
||||
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
|
||||
|
||||
{ "motor_pwm_rate", VAR_UINT16, &masterConfig.motor_pwm_rate, 50, 32000 },
|
||||
{ "servo_pwm_rate", VAR_UINT16, &masterConfig.servo_pwm_rate, 50, 498 },
|
||||
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, 50, 32000 },
|
||||
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, 50, 498 },
|
||||
|
||||
{ "retarded_arm", VAR_UINT8, &masterConfig.retarded_arm, 0, 1 },
|
||||
{ "small_angle", VAR_UINT8, &masterConfig.small_angle, 0, 180 },
|
||||
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
|
||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
|
||||
|
||||
{ "flaps_speed", VAR_UINT8, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
||||
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
||||
|
||||
{ "fixedwing_althold_dir", VAR_INT8, &masterConfig.fixedwing_althold_dir, -1, 1 },
|
||||
{ "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE | MASTER_VALUE, &masterConfig.fixedwing_althold_dir, -1, 1 },
|
||||
|
||||
{ "serial_port_1_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_1_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_2_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_2_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_3_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_3_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_4_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_4_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_1_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_1_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_2_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_3_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_4_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#if (SERIAL_PORT_COUNT > 4)
|
||||
{ "serial_port_5_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_5_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
{ "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_5_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||
#endif
|
||||
|
||||
{ "reboot_character", VAR_UINT8, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
{ "msp_baudrate", VAR_UINT32, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
|
||||
{ "cli_baudrate", VAR_UINT32, &masterConfig.serialConfig.cli_baudrate, 1200, 115200 },
|
||||
{ "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
{ "msp_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
|
||||
{ "cli_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.cli_baudrate, 1200, 115200 },
|
||||
|
||||
#ifdef GPS
|
||||
{ "gps_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
|
||||
{ "gps_passthrough_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
|
||||
{ "gps_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
|
||||
{ "gps_passthrough_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
|
||||
|
||||
{ "gps_provider", VAR_UINT8, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
||||
{ "gps_sbas_mode", VAR_UINT8, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
||||
{ "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
||||
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
||||
|
||||
|
||||
{ "gps_pos_p", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_i", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_d", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDPOS], 0, 200 },
|
||||
{ "gps_posr_p", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDPOSR], 0, 200 },
|
||||
{ "gps_posr_i", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDPOSR], 0, 200 },
|
||||
{ "gps_posr_d", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDPOSR], 0, 200 },
|
||||
{ "gps_nav_p", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDNAVR], 0, 200 },
|
||||
{ "gps_nav_i", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDNAVR], 0, 200 },
|
||||
{ "gps_nav_d", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDNAVR], 0, 200 },
|
||||
{ "gps_wp_radius", VAR_UINT16, ¤tProfile.gpsProfile.gps_wp_radius, 0, 2000 },
|
||||
{ "nav_controls_heading", VAR_UINT8, ¤tProfile.gpsProfile.nav_controls_heading, 0, 1 },
|
||||
{ "nav_speed_min", VAR_UINT16, ¤tProfile.gpsProfile.nav_speed_min, 10, 2000 },
|
||||
{ "nav_speed_max", VAR_UINT16, ¤tProfile.gpsProfile.nav_speed_max, 10, 2000 },
|
||||
{ "nav_slew_rate", VAR_UINT8, ¤tProfile.gpsProfile.nav_slew_rate, 0, 100 },
|
||||
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDPOS], 0, 200 },
|
||||
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDPOS], 0, 200 },
|
||||
{ "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDPOSR], 0, 200 },
|
||||
{ "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDPOSR], 0, 200 },
|
||||
{ "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDPOSR], 0, 200 },
|
||||
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDNAVR], 0, 200 },
|
||||
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDNAVR], 0, 200 },
|
||||
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDNAVR], 0, 200 },
|
||||
{ "gps_wp_radius", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.gpsProfile.gps_wp_radius, 0, 2000 },
|
||||
{ "nav_controls_heading", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.gpsProfile.nav_controls_heading, 0, 1 },
|
||||
{ "nav_speed_min", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.gpsProfile.nav_speed_min, 10, 2000 },
|
||||
{ "nav_speed_max", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.gpsProfile.nav_speed_max, 10, 2000 },
|
||||
{ "nav_slew_rate", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.gpsProfile.nav_slew_rate, 0, 100 },
|
||||
#endif
|
||||
|
||||
{ "serialrx_provider", VAR_UINT8, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||
|
||||
{ "telemetry_provider", VAR_UINT8, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||
{ "telemetry_switch", VAR_UINT8, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
||||
{ "frsky_inversion", VAR_UINT8, &masterConfig.telemetryConfig.frsky_inversion, 0, 1 },
|
||||
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
||||
{ "frsky_inversion", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_inversion, 0, 1 },
|
||||
|
||||
{ "vbat_scale", VAR_UINT8, &masterConfig.batteryConfig.vbatscale, 10, 200 },
|
||||
{ "vbat_max_cell_voltage", VAR_UINT8, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbat_min_cell_voltage", VAR_UINT8, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
|
||||
{ "current_meter_scale", VAR_UINT16, &masterConfig.batteryConfig.currentMeterScale, 1, 10000 },
|
||||
{ "current_meter_offset", VAR_UINT16, &masterConfig.batteryConfig.currentMeterOffset, 0, 1650 },
|
||||
{ "multiwii_current_meter_output", VAR_UINT8, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
|
||||
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, 10, 200 },
|
||||
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
|
||||
{ "current_meter_scale", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, 1, 10000 },
|
||||
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 1650 },
|
||||
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
|
||||
|
||||
|
||||
{ "align_gyro", VAR_UINT8, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
|
||||
{ "align_acc", VAR_UINT8, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },
|
||||
{ "align_mag", VAR_UINT8, &masterConfig.sensorAlignmentConfig.mag_align, 0, 8 },
|
||||
{ "align_gyro", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
|
||||
{ "align_acc", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },
|
||||
{ "align_mag", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.mag_align, 0, 8 },
|
||||
|
||||
{ "align_board_roll", VAR_INT16, &masterConfig.boardAlignment.rollDegrees, -180, 360 },
|
||||
{ "align_board_pitch", VAR_INT16, &masterConfig.boardAlignment.pitchDegrees, -180, 360 },
|
||||
{ "align_board_yaw", VAR_INT16, &masterConfig.boardAlignment.yawDegrees, -180, 360 },
|
||||
{ "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, -180, 360 },
|
||||
{ "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, -180, 360 },
|
||||
{ "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, -180, 360 },
|
||||
|
||||
{ "max_angle_inclination", VAR_UINT16, &masterConfig.max_angle_inclination, 100, 900 },
|
||||
{ "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, 100, 900 },
|
||||
|
||||
{ "gyro_lpf", VAR_UINT16, &masterConfig.gyro_lpf, 0, 256 },
|
||||
{ "moron_threshold", VAR_UINT8, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16, &masterConfig.gyro_cmpf_factor, 100, 1000 },
|
||||
{ "gyro_cmpfm_factor", VAR_UINT16, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
|
||||
{ "gyro_lpf", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_lpf, 0, 256 },
|
||||
{ "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpf_factor, 100, 1000 },
|
||||
{ "gyro_cmpfm_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
|
||||
|
||||
{ "alt_hold_deadband", VAR_UINT8, ¤tProfile.alt_hold_deadband, 1, 250 },
|
||||
{ "alt_hold_fast_change", VAR_UINT8, ¤tProfile.alt_hold_fast_change, 0, 1 },
|
||||
{ "alt_hold_deadband", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.alt_hold_deadband, 1, 250 },
|
||||
{ "alt_hold_fast_change", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.alt_hold_fast_change, 0, 1 },
|
||||
|
||||
{ "throttle_correction_value", VAR_UINT8, ¤tProfile.throttle_correction_value, 0, 150 },
|
||||
{ "throttle_correction_angle", VAR_UINT16, ¤tProfile.throttle_correction_angle, 1, 900 },
|
||||
{ "throttle_correction_value", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.throttle_correction_value, 0, 150 },
|
||||
{ "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.throttle_correction_angle, 1, 900 },
|
||||
|
||||
{ "deadband", VAR_UINT8, ¤tProfile.deadband, 0, 32 },
|
||||
{ "yaw_deadband", VAR_UINT8, ¤tProfile.yaw_deadband, 0, 100 },
|
||||
{ "yaw_control_direction", VAR_INT8, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
{ "deadband", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.deadband, 0, 32 },
|
||||
{ "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.yaw_deadband, 0, 100 },
|
||||
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
|
||||
{ "yaw_direction", VAR_INT8, ¤tProfile.mixerConfig.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8, ¤tProfile.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
{ "yaw_direction", VAR_INT8 | PROFILE_VALUE, ¤tProfile.mixerConfig.yaw_direction, -1, 1 },
|
||||
{ "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, ¤tProfile.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
|
||||
{ "rc_rate", VAR_UINT8, ¤tProfile.controlRateConfig.rcRate8, 0, 250 },
|
||||
{ "rc_expo", VAR_UINT8, ¤tProfile.controlRateConfig.rcExpo8, 0, 100 },
|
||||
{ "thr_mid", VAR_UINT8, ¤tProfile.controlRateConfig.thrMid8, 0, 100 },
|
||||
{ "thr_expo", VAR_UINT8, ¤tProfile.controlRateConfig.thrExpo8, 0, 100 },
|
||||
{ "roll_pitch_rate", VAR_UINT8, ¤tProfile.controlRateConfig.rollPitchRate, 0, 100 },
|
||||
{ "yaw_rate", VAR_UINT8, ¤tProfile.controlRateConfig.yawRate, 0, 100 },
|
||||
{ "tpa_rate", VAR_UINT8, ¤tProfile.dynThrPID, 0, 100},
|
||||
{ "tpa_breakpoint", VAR_UINT16, ¤tProfile.tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||
{ "rc_rate", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.rcRate8, 0, 250 },
|
||||
{ "rc_expo", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.rcExpo8, 0, 100 },
|
||||
{ "thr_mid", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.thrMid8, 0, 100 },
|
||||
{ "thr_expo", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.thrExpo8, 0, 100 },
|
||||
{ "roll_pitch_rate", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.rollPitchRate, 0, 100 },
|
||||
{ "yaw_rate", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.controlRateConfig.yawRate, 0, 100 },
|
||||
{ "tpa_rate", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.dynThrPID, 0, 100},
|
||||
{ "tpa_breakpoint", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||
|
||||
{ "failsafe_delay", VAR_UINT8, ¤tProfile.failsafeConfig.failsafe_delay, 0, 200 },
|
||||
{ "failsafe_off_delay", VAR_UINT8, ¤tProfile.failsafeConfig.failsafe_off_delay, 0, 200 },
|
||||
{ "failsafe_throttle", VAR_UINT16, ¤tProfile.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||
{ "failsafe_min_usec", VAR_UINT16, ¤tProfile.failsafeConfig.failsafe_min_usec, 100, PWM_RANGE_MAX },
|
||||
{ "failsafe_max_usec", VAR_UINT16, ¤tProfile.failsafeConfig.failsafe_max_usec, 100, PWM_RANGE_MAX + (PWM_RANGE_MAX - PWM_RANGE_MIN) },
|
||||
{ "failsafe_delay", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.failsafeConfig.failsafe_delay, 0, 200 },
|
||||
{ "failsafe_off_delay", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.failsafeConfig.failsafe_off_delay, 0, 200 },
|
||||
{ "failsafe_throttle", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||
{ "failsafe_min_usec", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.failsafeConfig.failsafe_min_usec, 100, PWM_RANGE_MAX },
|
||||
{ "failsafe_max_usec", VAR_UINT16 | PROFILE_VALUE, ¤tProfile.failsafeConfig.failsafe_max_usec, 100, PWM_RANGE_MAX + (PWM_RANGE_MAX - PWM_RANGE_MIN) },
|
||||
|
||||
{ "gimbal_flags", VAR_UINT8, ¤tProfile.gimbalConfig.gimbal_flags, 0, 255},
|
||||
{ "gimbal_flags", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.gimbalConfig.gimbal_flags, 0, 255},
|
||||
|
||||
{ "acc_hardware", VAR_UINT8, &masterConfig.acc_hardware, 0, 5 },
|
||||
{ "acc_lpf_factor", VAR_UINT8, ¤tProfile.acc_lpf_factor, 0, 250 },
|
||||
{ "accxy_deadband", VAR_UINT8, ¤tProfile.accDeadband.xy, 0, 100 },
|
||||
{ "accz_deadband", VAR_UINT8, ¤tProfile.accDeadband.z, 0, 100 },
|
||||
{ "accz_lpf_cutoff", VAR_FLOAT, ¤tProfile.accz_lpf_cutoff, 1, 20 },
|
||||
{ "acc_unarmedcal", VAR_UINT8, ¤tProfile.acc_unarmedcal, 0, 1 },
|
||||
{ "acc_trim_pitch", VAR_INT16, ¤tProfile.accelerometerTrims.values.pitch, -300, 300 },
|
||||
{ "acc_trim_roll", VAR_INT16, ¤tProfile.accelerometerTrims.values.roll, -300, 300 },
|
||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_hardware, 0, 5 },
|
||||
{ "acc_lpf_factor", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.acc_lpf_factor, 0, 250 },
|
||||
{ "accxy_deadband", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.accDeadband.xy, 0, 100 },
|
||||
{ "accz_deadband", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.accDeadband.z, 0, 100 },
|
||||
{ "accz_lpf_cutoff", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.accz_lpf_cutoff, 1, 20 },
|
||||
{ "acc_unarmedcal", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.acc_unarmedcal, 0, 1 },
|
||||
{ "acc_trim_pitch", VAR_INT16 | PROFILE_VALUE, ¤tProfile.accelerometerTrims.values.pitch, -300, 300 },
|
||||
{ "acc_trim_roll", VAR_INT16 | PROFILE_VALUE, ¤tProfile.accelerometerTrims.values.roll, -300, 300 },
|
||||
|
||||
{ "baro_tab_size", VAR_UINT8, ¤tProfile.barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
|
||||
{ "baro_noise_lpf", VAR_FLOAT, ¤tProfile.barometerConfig.baro_noise_lpf, 0, 1 },
|
||||
{ "baro_cf_vel", VAR_FLOAT, ¤tProfile.barometerConfig.baro_cf_vel, 0, 1 },
|
||||
{ "baro_cf_alt", VAR_FLOAT, ¤tProfile.barometerConfig.baro_cf_alt, 0, 1 },
|
||||
{ "baro_tab_size", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
|
||||
{ "baro_noise_lpf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.barometerConfig.baro_noise_lpf, 0, 1 },
|
||||
{ "baro_cf_vel", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.barometerConfig.baro_cf_vel, 0, 1 },
|
||||
{ "baro_cf_alt", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.barometerConfig.baro_cf_alt, 0, 1 },
|
||||
|
||||
{ "mag_declination", VAR_INT16, ¤tProfile.mag_declination, -18000, 18000 },
|
||||
{ "mag_declination", VAR_INT16 | PROFILE_VALUE, ¤tProfile.mag_declination, -18000, 18000 },
|
||||
|
||||
{ "pid_controller", VAR_UINT8, ¤tProfile.pidController, 0, 2 },
|
||||
{ "pid_controller", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidController, 0, 2 },
|
||||
|
||||
{ "p_pitch", VAR_UINT8, ¤tProfile.pidProfile.P8[PITCH], 0, 200 },
|
||||
{ "i_pitch", VAR_UINT8, ¤tProfile.pidProfile.I8[PITCH], 0, 200 },
|
||||
{ "d_pitch", VAR_UINT8, ¤tProfile.pidProfile.D8[PITCH], 0, 200 },
|
||||
{ "p_roll", VAR_UINT8, ¤tProfile.pidProfile.P8[ROLL], 0, 200 },
|
||||
{ "i_roll", VAR_UINT8, ¤tProfile.pidProfile.I8[ROLL], 0, 200 },
|
||||
{ "d_roll", VAR_UINT8, ¤tProfile.pidProfile.D8[ROLL], 0, 200 },
|
||||
{ "p_yaw", VAR_UINT8, ¤tProfile.pidProfile.P8[YAW], 0, 200 },
|
||||
{ "i_yaw", VAR_UINT8, ¤tProfile.pidProfile.I8[YAW], 0, 200 },
|
||||
{ "d_yaw", VAR_UINT8, ¤tProfile.pidProfile.D8[YAW], 0, 200 },
|
||||
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PITCH], 0, 200 },
|
||||
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PITCH], 0, 200 },
|
||||
{ "d_pitch", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PITCH], 0, 200 },
|
||||
{ "p_roll", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[ROLL], 0, 200 },
|
||||
{ "i_roll", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[ROLL], 0, 200 },
|
||||
{ "d_roll", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[ROLL], 0, 200 },
|
||||
{ "p_yaw", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[YAW], 0, 200 },
|
||||
{ "i_yaw", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[YAW], 0, 200 },
|
||||
{ "d_yaw", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[YAW], 0, 200 },
|
||||
|
||||
{ "p_pitchf", VAR_FLOAT, ¤tProfile.pidProfile.P_f[PITCH], 0, 100 },
|
||||
{ "i_pitchf", VAR_FLOAT, ¤tProfile.pidProfile.I_f[PITCH], 0, 100 },
|
||||
{ "d_pitchf", VAR_FLOAT, ¤tProfile.pidProfile.D_f[PITCH], 0, 100 },
|
||||
{ "p_rollf", VAR_FLOAT, ¤tProfile.pidProfile.P_f[ROLL], 0, 100 },
|
||||
{ "i_rollf", VAR_FLOAT, ¤tProfile.pidProfile.I_f[ROLL], 0, 100 },
|
||||
{ "d_rollf", VAR_FLOAT, ¤tProfile.pidProfile.D_f[ROLL], 0, 100 },
|
||||
{ "p_yawf", VAR_FLOAT, ¤tProfile.pidProfile.P_f[YAW], 0, 100 },
|
||||
{ "i_yawf", VAR_FLOAT, ¤tProfile.pidProfile.I_f[YAW], 0, 100 },
|
||||
{ "d_yawf", VAR_FLOAT, ¤tProfile.pidProfile.D_f[YAW], 0, 100 },
|
||||
{ "p_pitchf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.P_f[PITCH], 0, 100 },
|
||||
{ "i_pitchf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.I_f[PITCH], 0, 100 },
|
||||
{ "d_pitchf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.D_f[PITCH], 0, 100 },
|
||||
{ "p_rollf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.P_f[ROLL], 0, 100 },
|
||||
{ "i_rollf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.I_f[ROLL], 0, 100 },
|
||||
{ "d_rollf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.D_f[ROLL], 0, 100 },
|
||||
{ "p_yawf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.P_f[YAW], 0, 100 },
|
||||
{ "i_yawf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.I_f[YAW], 0, 100 },
|
||||
{ "d_yawf", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.D_f[YAW], 0, 100 },
|
||||
|
||||
{ "level_horizon", VAR_FLOAT, ¤tProfile.pidProfile.H_level, 0, 10 },
|
||||
{ "level_angle", VAR_FLOAT, ¤tProfile.pidProfile.A_level, 0, 10 },
|
||||
{ "level_horizon", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.H_level, 0, 10 },
|
||||
{ "level_angle", VAR_FLOAT | PROFILE_VALUE, ¤tProfile.pidProfile.A_level, 0, 10 },
|
||||
|
||||
{ "p_alt", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDALT], 0, 200 },
|
||||
{ "i_alt", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDALT], 0, 200 },
|
||||
{ "d_alt", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDALT], 0, 200 },
|
||||
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDALT], 0, 200 },
|
||||
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDALT], 0, 200 },
|
||||
{ "d_alt", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDALT], 0, 200 },
|
||||
|
||||
{ "p_level", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDLEVEL], 0, 200 },
|
||||
{ "i_level", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDLEVEL], 0, 200 },
|
||||
{ "d_level", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDLEVEL], 0, 200 },
|
||||
{ "p_level", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDLEVEL], 0, 200 },
|
||||
{ "i_level", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDLEVEL], 0, 200 },
|
||||
{ "d_level", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDLEVEL], 0, 200 },
|
||||
|
||||
{ "p_vel", VAR_UINT8, ¤tProfile.pidProfile.P8[PIDVEL], 0, 200 },
|
||||
{ "i_vel", VAR_UINT8, ¤tProfile.pidProfile.I8[PIDVEL], 0, 200 },
|
||||
{ "d_vel", VAR_UINT8, ¤tProfile.pidProfile.D8[PIDVEL], 0, 200 },
|
||||
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.P8[PIDVEL], 0, 200 },
|
||||
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.I8[PIDVEL], 0, 200 },
|
||||
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, ¤tProfile.pidProfile.D8[PIDVEL], 0, 200 },
|
||||
};
|
||||
|
||||
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
||||
|
@ -439,12 +445,12 @@ static void cliCMix(char *cmdline)
|
|||
len = strlen(++ptr);
|
||||
for (i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL) {
|
||||
cliPrint("Invalid mixer type...\r\n");
|
||||
cliPrint("Invalid mixer type\r\n");
|
||||
break;
|
||||
}
|
||||
if (strncasecmp(ptr, mixerNames[i], len) == 0) {
|
||||
mixerLoadMix(i, masterConfig.customMixer);
|
||||
printf("Loaded %s mix...\r\n", mixerNames[i]);
|
||||
printf("Loaded %s mix\r\n", mixerNames[i]);
|
||||
cliCMix("");
|
||||
break;
|
||||
}
|
||||
|
@ -485,76 +491,116 @@ static void cliCMix(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void dumpValues(uint8_t mask)
|
||||
{
|
||||
uint32_t i;
|
||||
const clivalue_t *value;
|
||||
for (i = 0; i < VALUE_COUNT; i++) {
|
||||
value = &valueTable[i];
|
||||
|
||||
if ((value->type & mask) == 0) {
|
||||
continue;
|
||||
}
|
||||
|
||||
printf("set %s = ", valueTable[i].name);
|
||||
cliPrintVar(value, 0);
|
||||
cliPrint("\r\n");
|
||||
}
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
DUMP_MASTER = (1 << 0),
|
||||
DUMP_PROFILE = (1 << 1)
|
||||
} dumpFlags_e;
|
||||
|
||||
#define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE)
|
||||
|
||||
|
||||
static const char* const sectionBreak = "\r\n";
|
||||
|
||||
#define printSectionBreak() printf((char *)sectionBreak)
|
||||
|
||||
static void cliDump(char *cmdline)
|
||||
{
|
||||
unsigned int i;
|
||||
char buf[16];
|
||||
float thr, roll, pitch, yaw;
|
||||
uint32_t mask;
|
||||
const clivalue_t *setval;
|
||||
|
||||
UNUSED(cmdline);
|
||||
uint8_t dumpMask = DUMP_ALL;
|
||||
if (strcasecmp(cmdline, "master") == 0) {
|
||||
dumpMask = DUMP_MASTER; // only
|
||||
}
|
||||
if (strcasecmp(cmdline, "profile") == 0) {
|
||||
dumpMask = DUMP_PROFILE; // only
|
||||
}
|
||||
|
||||
printf("Current Config: Copy everything below here...\r\n");
|
||||
if (dumpMask & DUMP_MASTER) {
|
||||
printf("\r\n# dump master\r\n");
|
||||
printf("\r\n# mixer\r\n");
|
||||
|
||||
// print out aux switches
|
||||
cliAux("");
|
||||
printf("mixer %s\r\n", mixerNames[masterConfig.mixerConfiguration - 1]);
|
||||
|
||||
// print out current motor mix
|
||||
printf("mixer %s\r\n", mixerNames[masterConfig.mixerConfiguration - 1]);
|
||||
|
||||
// print custom mix if exists
|
||||
if (masterConfig.customMixer[0].throttle != 0.0f) {
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
if (masterConfig.customMixer[i].throttle == 0.0f)
|
||||
break;
|
||||
thr = masterConfig.customMixer[i].throttle;
|
||||
roll = masterConfig.customMixer[i].roll;
|
||||
pitch = masterConfig.customMixer[i].pitch;
|
||||
yaw = masterConfig.customMixer[i].yaw;
|
||||
printf("cmix %d", i + 1);
|
||||
if (thr < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(thr, buf));
|
||||
if (roll < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(roll, buf));
|
||||
if (pitch < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(pitch, buf));
|
||||
if (yaw < 0)
|
||||
printf(" ");
|
||||
printf("%s\r\n", ftoa(yaw, buf));
|
||||
if (masterConfig.customMixer[0].throttle != 0.0f) {
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
if (masterConfig.customMixer[i].throttle == 0.0f)
|
||||
break;
|
||||
thr = masterConfig.customMixer[i].throttle;
|
||||
roll = masterConfig.customMixer[i].roll;
|
||||
pitch = masterConfig.customMixer[i].pitch;
|
||||
yaw = masterConfig.customMixer[i].yaw;
|
||||
printf("cmix %d", i + 1);
|
||||
if (thr < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(thr, buf));
|
||||
if (roll < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(roll, buf));
|
||||
if (pitch < 0)
|
||||
printf(" ");
|
||||
printf("%s", ftoa(pitch, buf));
|
||||
if (yaw < 0)
|
||||
printf(" ");
|
||||
printf("%s\r\n", ftoa(yaw, buf));
|
||||
}
|
||||
printf("cmix %d 0 0 0 0\r\n", i + 1);
|
||||
}
|
||||
printf("cmix %d 0 0 0 0\r\n", i + 1);
|
||||
|
||||
printf("\r\n\r\n# feature\r\n");
|
||||
|
||||
mask = featureMask();
|
||||
for (i = 0; ; i++) { // disable all feature first
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
printf("feature -%s\r\n", featureNames[i]);
|
||||
}
|
||||
for (i = 0; ; i++) { // reenable what we want.
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
if (mask & (1 << i))
|
||||
printf("feature %s\r\n", featureNames[i]);
|
||||
}
|
||||
|
||||
printf("\r\n\r\n# map\r\n");
|
||||
|
||||
for (i = 0; i < 8; i++)
|
||||
buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
|
||||
buf[i] = '\0';
|
||||
printf("map %s\r\n", buf);
|
||||
|
||||
printSectionBreak();
|
||||
dumpValues(MASTER_VALUE);
|
||||
}
|
||||
|
||||
// print enabled features
|
||||
mask = featureMask();
|
||||
for (i = 0; ; i++) { // disable all feature first
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
printf("feature -%s\r\n", featureNames[i]);
|
||||
}
|
||||
for (i = 0; ; i++) { // reenable what we want.
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
if (mask & (1 << i))
|
||||
printf("feature %s\r\n", featureNames[i]);
|
||||
}
|
||||
if (dumpMask & DUMP_PROFILE) {
|
||||
printf("\r\n# dump profile\r\n");
|
||||
printf("\r\n# aux\r\n");
|
||||
|
||||
// print RC MAPPING
|
||||
for (i = 0; i < 8; i++)
|
||||
buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
|
||||
buf[i] = '\0';
|
||||
printf("map %s\r\n", buf);
|
||||
cliAux("");
|
||||
|
||||
// print settings
|
||||
for (i = 0; i < VALUE_COUNT; i++) {
|
||||
setval = &valueTable[i];
|
||||
printf("set %s = ", valueTable[i].name);
|
||||
cliPrintVar(setval, 0);
|
||||
cliPrint("\r\n");
|
||||
printSectionBreak();
|
||||
|
||||
dumpValues(PROFILE_VALUE);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -569,7 +615,7 @@ static void cliEnter(void)
|
|||
|
||||
static void cliExit(char *cmdline)
|
||||
{
|
||||
cliPrint("\r\nLeaving CLI mode...\r\n");
|
||||
cliPrint("\r\nLeaving CLI mode\r\n");
|
||||
*cliBuffer = '\0';
|
||||
bufferIndex = 0;
|
||||
cliMode = 0;
|
||||
|
@ -621,7 +667,7 @@ static void cliFeature(char *cmdline)
|
|||
|
||||
for (i = 0; ; i++) {
|
||||
if (featureNames[i] == NULL) {
|
||||
cliPrint("Invalid feature name...\r\n");
|
||||
cliPrint("Invalid feature name\r\n");
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -737,7 +783,7 @@ static void cliMixer(char *cmdline)
|
|||
|
||||
for (i = 0; ; i++) {
|
||||
if (mixerNames[i] == NULL) {
|
||||
cliPrint("Invalid mixer type...\r\n");
|
||||
cliPrint("Invalid mixer type\r\n");
|
||||
break;
|
||||
}
|
||||
if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
|
||||
|
@ -815,7 +861,7 @@ static void cliProfile(char *cmdline)
|
|||
}
|
||||
|
||||
static void cliReboot(void) {
|
||||
cliPrint("\r\nRebooting...");
|
||||
cliPrint("\r\nRebooting");
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
systemReset(false);
|
||||
}
|
||||
|
@ -824,7 +870,7 @@ static void cliSave(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
cliPrint("Saving...");
|
||||
cliPrint("Saving");
|
||||
copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
|
||||
writeEEPROM();
|
||||
cliReboot();
|
||||
|
@ -834,7 +880,7 @@ static void cliDefaults(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
cliPrint("Resetting to defaults...");
|
||||
cliPrint("Resetting to defaults");
|
||||
resetEEPROM();
|
||||
cliReboot();
|
||||
}
|
||||
|
@ -855,7 +901,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
|||
int32_t value = 0;
|
||||
char buf[8];
|
||||
|
||||
switch (var->type) {
|
||||
switch (var->type & VALUE_TYPE_MASK) {
|
||||
case VAR_UINT8:
|
||||
value = *(uint8_t *)var->ptr;
|
||||
break;
|
||||
|
@ -891,7 +937,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
|||
|
||||
static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
|
||||
{
|
||||
switch (var->type) {
|
||||
switch (var->type & VALUE_TYPE_MASK) {
|
||||
case VAR_UINT8:
|
||||
case VAR_INT8:
|
||||
*(char *)var->ptr = (char)value.int_value;
|
||||
|
@ -949,7 +995,7 @@ static void cliSet(char *cmdline)
|
|||
if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
|
||||
if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT?
|
||||
int_float_value_t tmp;
|
||||
if (valueTable[i].type == VAR_FLOAT)
|
||||
if (valueTable[i].type & VAR_FLOAT)
|
||||
tmp.float_value = valuef;
|
||||
else
|
||||
tmp.int_value = value;
|
||||
|
@ -957,12 +1003,12 @@ static void cliSet(char *cmdline)
|
|||
printf("%s set to ", valueTable[i].name);
|
||||
cliPrintVar(val, 0);
|
||||
} else {
|
||||
cliPrint("ERR: Value assignment out of range\r\n");
|
||||
cliPrint("Value assignment out of range\r\n");
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
cliPrint("ERR: Unknown variable name\r\n");
|
||||
cliPrint("Unknown variable name\r\n");
|
||||
} else {
|
||||
// no equals, check for matching variables.
|
||||
cliGet(cmdline);
|
||||
|
@ -991,7 +1037,7 @@ static void cliGet(char *cmdline)
|
|||
return;
|
||||
}
|
||||
|
||||
cliPrint("ERR: Unknown variable name\r\n");
|
||||
cliPrint("Unknown variable name\r\n");
|
||||
}
|
||||
|
||||
static void cliStatus(char *cmdline)
|
||||
|
@ -1026,7 +1072,7 @@ static void cliVersion(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
cliPrint("Afro32 CLI version 2.2 " __DATE__ " / " __TIME__ " - (" __FORKNAME__ ")");
|
||||
cliPrint("Cleanflight - " __DATE__ " / " __TIME__ " - (" __TARGET__ ")");
|
||||
}
|
||||
|
||||
void cliProcess(void)
|
||||
|
@ -1094,7 +1140,7 @@ void cliProcess(void)
|
|||
if (cmd)
|
||||
cmd->func(cliBuffer + strlen(cmd->name) + 1);
|
||||
else
|
||||
cliPrint("ERR: Unknown command, try 'help'");
|
||||
cliPrint("Unknown command, try 'help'");
|
||||
|
||||
memset(cliBuffer, 0, sizeof(cliBuffer));
|
||||
bufferIndex = 0;
|
||||
|
|
Loading…
Reference in New Issue