Arduino_VESC_Library
mc_configuration Struct Reference

#include <vesc_types.h>

Public Attributes

uint32_t signature
 
uint8_t pwm_mode
 
uint8_t comm_mode
 
uint8_t motor_type
 
uint8_t sensor_mode
 
float l_current_max
 
float l_current_min
 
float l_in_current_max
 
float l_in_current_min
 
float l_abs_current_max
 
float l_min_erpm
 
float l_max_erpm
 
float l_erpm_start
 
float l_max_erpm_fbrake
 
float l_max_erpm_fbrake_cc
 
float l_min_vin
 
float l_max_vin
 
float l_battery_cut_start
 
float l_battery_cut_end
 
bool l_slow_abs_current
 
float l_temp_fet_start
 
float l_temp_fet_end
 
float l_temp_motor_start
 
float l_temp_motor_end
 
float l_temp_accel_dec
 
float l_min_duty
 
float l_max_duty
 
float l_watt_max
 
float l_watt_min
 
float l_current_max_scale
 
float l_current_min_scale
 
float lo_current_max
 
float lo_current_min
 
float lo_in_current_max
 
float lo_in_current_min
 
float lo_current_motor_max_now
 
float lo_current_motor_min_now
 
float sl_min_erpm
 
float sl_min_erpm_cycle_int_limit
 
float sl_max_fullbreak_current_dir_change
 
float sl_cycle_int_limit
 
float sl_phase_advance_at_br
 
float sl_cycle_int_rpm_br
 
float sl_bemf_coupling_k
 
int8_t hall_table [8]
 
float hall_sl_erpm
 
float foc_current_kp
 
float foc_current_ki
 
float foc_f_sw
 
float foc_dt_us
 
float foc_encoder_offset
 
bool foc_encoder_inverted
 
float foc_encoder_ratio
 
float foc_encoder_sin_offset
 
float foc_encoder_sin_gain
 
float foc_encoder_cos_offset
 
float foc_encoder_cos_gain
 
float foc_encoder_sincos_filter_constant
 
float foc_motor_l
 
float foc_motor_r
 
float foc_motor_flux_linkage
 
float foc_observer_gain
 
float foc_observer_gain_slow
 
float foc_pll_kp
 
float foc_pll_ki
 
float foc_duty_dowmramp_kp
 
float foc_duty_dowmramp_ki
 
float foc_openloop_rpm
 
float foc_sl_openloop_hyst
 
float foc_sl_openloop_time
 
float foc_sl_d_current_duty
 
float foc_sl_d_current_factor
 
uint8_t foc_sensor_mode
 
uint8_t foc_hall_table [8]
 
float foc_sl_erpm
 
bool foc_sample_v0_v7
 
bool foc_sample_high_current
 
float foc_sat_comp
 
bool foc_temp_comp
 
float foc_temp_comp_base_temp
 
float foc_current_filter_const
 
int gpd_buffer_notify_left
 
int gpd_buffer_interpol
 
float gpd_current_filter_const
 
float gpd_current_kp
 
float gpd_current_ki
 
float s_pid_kp
 
float s_pid_ki
 
float s_pid_kd
 
float s_pid_kd_filter
 
float s_pid_min_erpm
 
bool s_pid_allow_braking
 
float p_pid_kp
 
float p_pid_ki
 
float p_pid_kd
 
float p_pid_kd_filter
 
float p_pid_ang_div
 
float cc_startup_boost_duty
 
float cc_min_current
 
float cc_gain
 
float cc_ramp_step_max
 
int32_t m_fault_stop_time_ms
 
float m_duty_ramp_step
 
float m_current_backoff_gain
 
uint32_t m_encoder_counts
 
uint8_t m_sensor_port_mode
 
bool m_invert_direction
 
uint8_t m_drv8301_oc_mode
 
int m_drv8301_oc_adj
 
float m_bldc_f_sw_min
 
float m_bldc_f_sw_max
 
float m_dc_f_sw
 
float m_ntc_motor_beta
 
uint8_t m_out_aux_mode
 
uint8_t si_motor_poles
 
float si_gear_ratio
 
float si_wheel_diameter
 
uint8_t si_battery_type
 
int si_battery_cells
 
float si_battery_ah
 

Detailed Description

Definition at line 53 of file vesc_types.h.

Member Data Documentation

◆ cc_gain

float mc_configuration::cc_gain

Definition at line 163 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ cc_min_current

float mc_configuration::cc_min_current

Definition at line 162 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ cc_ramp_step_max

float mc_configuration::cc_ramp_step_max

Definition at line 164 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ cc_startup_boost_duty

float mc_configuration::cc_startup_boost_duty

Definition at line 161 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ comm_mode

uint8_t mc_configuration::comm_mode

Definition at line 57 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_current_filter_const

float mc_configuration::foc_current_filter_const

Definition at line 140 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_current_ki

float mc_configuration::foc_current_ki

Definition at line 107 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_current_kp

float mc_configuration::foc_current_kp

Definition at line 106 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_dt_us

float mc_configuration::foc_dt_us

Definition at line 109 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_duty_dowmramp_ki

float mc_configuration::foc_duty_dowmramp_ki

Definition at line 126 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_duty_dowmramp_kp

float mc_configuration::foc_duty_dowmramp_kp

Definition at line 125 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_cos_gain

float mc_configuration::foc_encoder_cos_gain

Definition at line 116 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_cos_offset

float mc_configuration::foc_encoder_cos_offset

Definition at line 115 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_inverted

bool mc_configuration::foc_encoder_inverted

Definition at line 111 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_offset

float mc_configuration::foc_encoder_offset

Definition at line 110 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_ratio

float mc_configuration::foc_encoder_ratio

Definition at line 112 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_sin_gain

float mc_configuration::foc_encoder_sin_gain

Definition at line 114 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_sin_offset

float mc_configuration::foc_encoder_sin_offset

Definition at line 113 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_encoder_sincos_filter_constant

float mc_configuration::foc_encoder_sincos_filter_constant

Definition at line 117 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_f_sw

float mc_configuration::foc_f_sw

Definition at line 108 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_hall_table

uint8_t mc_configuration::foc_hall_table[8]

Definition at line 133 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_motor_flux_linkage

float mc_configuration::foc_motor_flux_linkage

Definition at line 120 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_motor_l

float mc_configuration::foc_motor_l

Definition at line 118 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_motor_r

float mc_configuration::foc_motor_r

Definition at line 119 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_observer_gain

float mc_configuration::foc_observer_gain

Definition at line 121 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_observer_gain_slow

float mc_configuration::foc_observer_gain_slow

Definition at line 122 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_openloop_rpm

float mc_configuration::foc_openloop_rpm

Definition at line 127 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_pll_ki

float mc_configuration::foc_pll_ki

Definition at line 124 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_pll_kp

float mc_configuration::foc_pll_kp

Definition at line 123 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sample_high_current

bool mc_configuration::foc_sample_high_current

Definition at line 136 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sample_v0_v7

bool mc_configuration::foc_sample_v0_v7

Definition at line 135 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sat_comp

float mc_configuration::foc_sat_comp

Definition at line 137 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sensor_mode

uint8_t mc_configuration::foc_sensor_mode

Definition at line 132 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sl_d_current_duty

float mc_configuration::foc_sl_d_current_duty

Definition at line 130 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sl_d_current_factor

float mc_configuration::foc_sl_d_current_factor

Definition at line 131 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sl_erpm

float mc_configuration::foc_sl_erpm

Definition at line 134 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sl_openloop_hyst

float mc_configuration::foc_sl_openloop_hyst

Definition at line 128 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_sl_openloop_time

float mc_configuration::foc_sl_openloop_time

Definition at line 129 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_temp_comp

bool mc_configuration::foc_temp_comp

Definition at line 138 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ foc_temp_comp_base_temp

float mc_configuration::foc_temp_comp_base_temp

Definition at line 139 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ gpd_buffer_interpol

int mc_configuration::gpd_buffer_interpol

Definition at line 143 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ gpd_buffer_notify_left

int mc_configuration::gpd_buffer_notify_left

Definition at line 142 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ gpd_current_filter_const

float mc_configuration::gpd_current_filter_const

Definition at line 144 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ gpd_current_ki

float mc_configuration::gpd_current_ki

Definition at line 146 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ gpd_current_kp

float mc_configuration::gpd_current_kp

Definition at line 145 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ hall_sl_erpm

float mc_configuration::hall_sl_erpm

Definition at line 104 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ hall_table

int8_t mc_configuration::hall_table[8]

Definition at line 103 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_abs_current_max

float mc_configuration::l_abs_current_max

Definition at line 65 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_battery_cut_end

float mc_configuration::l_battery_cut_end

Definition at line 74 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_battery_cut_start

float mc_configuration::l_battery_cut_start

Definition at line 73 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_current_max

float mc_configuration::l_current_max

Definition at line 61 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_current_max_scale

float mc_configuration::l_current_max_scale

Definition at line 85 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_current_min

float mc_configuration::l_current_min

Definition at line 62 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_current_min_scale

float mc_configuration::l_current_min_scale

Definition at line 86 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_erpm_start

float mc_configuration::l_erpm_start

Definition at line 68 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_in_current_max

float mc_configuration::l_in_current_max

Definition at line 63 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_in_current_min

float mc_configuration::l_in_current_min

Definition at line 64 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_max_duty

float mc_configuration::l_max_duty

Definition at line 82 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_max_erpm

float mc_configuration::l_max_erpm

Definition at line 67 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_max_erpm_fbrake

float mc_configuration::l_max_erpm_fbrake

Definition at line 69 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_max_erpm_fbrake_cc

float mc_configuration::l_max_erpm_fbrake_cc

Definition at line 70 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_max_vin

float mc_configuration::l_max_vin

Definition at line 72 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_min_duty

float mc_configuration::l_min_duty

Definition at line 81 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_min_erpm

float mc_configuration::l_min_erpm

Definition at line 66 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_min_vin

float mc_configuration::l_min_vin

Definition at line 71 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_slow_abs_current

bool mc_configuration::l_slow_abs_current

Definition at line 75 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_temp_accel_dec

float mc_configuration::l_temp_accel_dec

Definition at line 80 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_temp_fet_end

float mc_configuration::l_temp_fet_end

Definition at line 77 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_temp_fet_start

float mc_configuration::l_temp_fet_start

Definition at line 76 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_temp_motor_end

float mc_configuration::l_temp_motor_end

Definition at line 79 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_temp_motor_start

float mc_configuration::l_temp_motor_start

Definition at line 78 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_watt_max

float mc_configuration::l_watt_max

Definition at line 83 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ l_watt_min

float mc_configuration::l_watt_min

Definition at line 84 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ lo_current_max

float mc_configuration::lo_current_max

Definition at line 88 of file vesc_types.h.

◆ lo_current_min

float mc_configuration::lo_current_min

Definition at line 89 of file vesc_types.h.

◆ lo_current_motor_max_now

float mc_configuration::lo_current_motor_max_now

Definition at line 92 of file vesc_types.h.

◆ lo_current_motor_min_now

float mc_configuration::lo_current_motor_min_now

Definition at line 93 of file vesc_types.h.

◆ lo_in_current_max

float mc_configuration::lo_in_current_max

Definition at line 90 of file vesc_types.h.

◆ lo_in_current_min

float mc_configuration::lo_in_current_min

Definition at line 91 of file vesc_types.h.

◆ m_bldc_f_sw_max

float mc_configuration::m_bldc_f_sw_max

Definition at line 175 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_bldc_f_sw_min

float mc_configuration::m_bldc_f_sw_min

Definition at line 174 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_current_backoff_gain

float mc_configuration::m_current_backoff_gain

Definition at line 168 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_dc_f_sw

float mc_configuration::m_dc_f_sw

Definition at line 176 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_drv8301_oc_adj

int mc_configuration::m_drv8301_oc_adj

Definition at line 173 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_drv8301_oc_mode

uint8_t mc_configuration::m_drv8301_oc_mode

Definition at line 172 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_duty_ramp_step

float mc_configuration::m_duty_ramp_step

Definition at line 167 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_encoder_counts

uint32_t mc_configuration::m_encoder_counts

Definition at line 169 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_fault_stop_time_ms

int32_t mc_configuration::m_fault_stop_time_ms

Definition at line 166 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_invert_direction

bool mc_configuration::m_invert_direction

Definition at line 171 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_ntc_motor_beta

float mc_configuration::m_ntc_motor_beta

Definition at line 177 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_out_aux_mode

uint8_t mc_configuration::m_out_aux_mode

Definition at line 178 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ m_sensor_port_mode

uint8_t mc_configuration::m_sensor_port_mode

Definition at line 170 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ motor_type

uint8_t mc_configuration::motor_type

Definition at line 58 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ p_pid_ang_div

float mc_configuration::p_pid_ang_div

Definition at line 159 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ p_pid_kd

float mc_configuration::p_pid_kd

Definition at line 157 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ p_pid_kd_filter

float mc_configuration::p_pid_kd_filter

Definition at line 158 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ p_pid_ki

float mc_configuration::p_pid_ki

Definition at line 156 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ p_pid_kp

float mc_configuration::p_pid_kp

Definition at line 155 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ pwm_mode

uint8_t mc_configuration::pwm_mode

Definition at line 56 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_allow_braking

bool mc_configuration::s_pid_allow_braking

Definition at line 153 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_kd

float mc_configuration::s_pid_kd

Definition at line 150 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_kd_filter

float mc_configuration::s_pid_kd_filter

Definition at line 151 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_ki

float mc_configuration::s_pid_ki

Definition at line 149 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_kp

float mc_configuration::s_pid_kp

Definition at line 148 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ s_pid_min_erpm

float mc_configuration::s_pid_min_erpm

Definition at line 152 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sensor_mode

uint8_t mc_configuration::sensor_mode

Definition at line 59 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_battery_ah

float mc_configuration::si_battery_ah

Definition at line 185 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_battery_cells

int mc_configuration::si_battery_cells

Definition at line 184 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_battery_type

uint8_t mc_configuration::si_battery_type

Definition at line 183 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_gear_ratio

float mc_configuration::si_gear_ratio

Definition at line 181 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_motor_poles

uint8_t mc_configuration::si_motor_poles

Definition at line 180 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ si_wheel_diameter

float mc_configuration::si_wheel_diameter

Definition at line 182 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ signature

uint32_t mc_configuration::signature

Definition at line 54 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_bemf_coupling_k

float mc_configuration::sl_bemf_coupling_k

Definition at line 101 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_cycle_int_limit

float mc_configuration::sl_cycle_int_limit

Definition at line 98 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_cycle_int_rpm_br

float mc_configuration::sl_cycle_int_rpm_br

Definition at line 100 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_max_fullbreak_current_dir_change

float mc_configuration::sl_max_fullbreak_current_dir_change

Definition at line 97 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_min_erpm

float mc_configuration::sl_min_erpm

Definition at line 95 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_min_erpm_cycle_int_limit

float mc_configuration::sl_min_erpm_cycle_int_limit

Definition at line 96 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().

◆ sl_phase_advance_at_br

float mc_configuration::sl_phase_advance_at_br

Definition at line 99 of file vesc_types.h.

Referenced by Vesc::getMotorConfiguration().


The documentation for this struct was generated from the following file: