Arduino_VESC_Library
Vesc Class Reference

vesc interface More...

#include <vesc.h>

Public Member Functions

 Vesc (void)
 
void init (HardwareSerial *uartPort, HardwareSerial *debugPort)
 init vesc interface More...
 
void setDuty (float duty)
 set duty cycle range 0.0% - 1.0% More...
 
void setCurrent (float current)
 set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncated if exeeds max motor current! More...
 
void setBrakeCurrent (float current)
 set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncated if exeeds max motor current! More...
 
void setRPM (int32_t rpm)
 set rpm to set 0 - MAX More...
 
void setPosition (float position)
 set rpm 0 - MAX More...
 
void setHandbrake (float current)
 set handbreak 0 - MAX More...
 
vesc_version getFirmwareVersion ()
 get firmware version More...
 
vesc_values getRealtimeValues ()
 get real time values More...
 
mc_configuration getMotorConfiguration ()
 get motor configuration More...
 
float getFetTemperature ()
 get MosFet temperature More...
 
float getMotorTemperature ()
 get motor temperature More...
 
float getAvgMotorCurrent ()
 get average motor current More...
 
float getAvgInputCurrent ()
 get average input current More...
 
float getResetAvgId ()
 get reset average id More...
 
float getResetAvgIq ()
 get reset average iq More...
 
float getDutyCycleNow ()
 get duty cycle now More...
 
float getRPM ()
 get rpm More...
 
float getInputVoltage ()
 get input voltage More...
 
float getAmpHours ()
 get amp hours More...
 
float getaAmpHoursCharged ()
 get amp hours charged More...
 
float getWattHours ()
 get watt hours More...
 
float getWattHoursCharged ()
 get watt hours charged More...
 
int32_t getTachometerValue ()
 get tachometer value More...
 
int32_t getTachometerAbsValue ()
 get tachometer abs value More...
 
uint8_t getFault ()
 get fault More...
 
float getPidPosNow ()
 get pid pos now More...
 
uint8_t getControllerId ()
 get controller id More...
 
float * getMosfetsTemperature ()
 get mosfets temperature More...
 
float getResetAvgVd ()
 get reset average vd More...
 
float getResetAvgVq ()
 get reset average vq More...
 

Private Member Functions

void sendPacket (unsigned char *data, unsigned int len)
 helper method to send packet More...
 
bool receivePacket (unsigned char *data)
 helper method to receive packet More...
 
bool getRealtimeValuesSelective (unsigned char *data, unsigned int index)
 helper method to retrieve single values from vesc More...
 

Private Attributes

HardwareSerial * uartPort = NULL
 
HardwareSerial * debugPort = NULL
 

Detailed Description

vesc interface

Definition at line 28 of file vesc.h.

Constructor & Destructor Documentation

◆ Vesc()

Vesc::Vesc ( void  )

Definition at line 21 of file vesc.cpp.

Member Function Documentation

◆ getaAmpHoursCharged()

float Vesc::getaAmpHoursCharged ( )

get amp hours charged

Returns
float amp hours charged

Definition at line 376 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getAmpHours()

float Vesc::getAmpHours ( )

get amp hours

Returns
float amp hours

Definition at line 359 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getAvgInputCurrent()

float Vesc::getAvgInputCurrent ( )

get average input current

Returns
float average input current

Definition at line 256 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getAvgMotorCurrent()

float Vesc::getAvgMotorCurrent ( )

get average motor current

Returns
float average motor current

Definition at line 239 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getControllerId()

uint8_t Vesc::getControllerId ( )

get controller id

Returns
uint8_t controller id

Definition at line 494 of file vesc.cpp.

References getRealtimeValuesSelective().

◆ getDutyCycleNow()

float Vesc::getDutyCycleNow ( )

get duty cycle now

Returns
float duty cycle now

Definition at line 307 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float16().

◆ getFault()

uint8_t Vesc::getFault ( )

get fault

Returns
uint8_t get fault

Definition at line 461 of file vesc.cpp.

References getRealtimeValuesSelective().

◆ getFetTemperature()

float Vesc::getFetTemperature ( )

get MosFet temperature

Returns
float temperature

Definition at line 205 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float16().

◆ getFirmwareVersion()

◆ getInputVoltage()

float Vesc::getInputVoltage ( )

get input voltage

Returns
float input voltage

Definition at line 341 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float16().

◆ getMosfetsTemperature()

float * Vesc::getMosfetsTemperature ( )

get mosfets temperature

Returns
float* temperature of the tree mosfets

Definition at line 510 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float16().

◆ getMotorConfiguration()

mc_configuration Vesc::getMotorConfiguration ( )

get motor configuration

Returns
mc_configuration

Definition at line 603 of file vesc.cpp.

References mc_configuration::cc_gain, mc_configuration::cc_min_current, mc_configuration::cc_ramp_step_max, mc_configuration::cc_startup_boost_duty, COMM_GET_MCCONF, mc_configuration::comm_mode, mc_configuration::foc_current_filter_const, mc_configuration::foc_current_ki, mc_configuration::foc_current_kp, mc_configuration::foc_dt_us, mc_configuration::foc_duty_dowmramp_ki, mc_configuration::foc_duty_dowmramp_kp, mc_configuration::foc_encoder_cos_gain, mc_configuration::foc_encoder_cos_offset, mc_configuration::foc_encoder_inverted, mc_configuration::foc_encoder_offset, mc_configuration::foc_encoder_ratio, mc_configuration::foc_encoder_sin_gain, mc_configuration::foc_encoder_sin_offset, mc_configuration::foc_encoder_sincos_filter_constant, mc_configuration::foc_f_sw, mc_configuration::foc_hall_table, mc_configuration::foc_motor_flux_linkage, mc_configuration::foc_motor_l, mc_configuration::foc_motor_r, mc_configuration::foc_observer_gain, mc_configuration::foc_observer_gain_slow, mc_configuration::foc_openloop_rpm, mc_configuration::foc_pll_ki, mc_configuration::foc_pll_kp, mc_configuration::foc_sample_high_current, mc_configuration::foc_sample_v0_v7, mc_configuration::foc_sat_comp, mc_configuration::foc_sensor_mode, mc_configuration::foc_sl_d_current_duty, mc_configuration::foc_sl_d_current_factor, mc_configuration::foc_sl_erpm, mc_configuration::foc_sl_openloop_hyst, mc_configuration::foc_sl_openloop_time, mc_configuration::foc_temp_comp, mc_configuration::foc_temp_comp_base_temp, mc_configuration::gpd_buffer_interpol, mc_configuration::gpd_buffer_notify_left, mc_configuration::gpd_current_filter_const, mc_configuration::gpd_current_ki, mc_configuration::gpd_current_kp, mc_configuration::hall_sl_erpm, mc_configuration::hall_table, mc_configuration::l_abs_current_max, mc_configuration::l_battery_cut_end, mc_configuration::l_battery_cut_start, mc_configuration::l_current_max, mc_configuration::l_current_max_scale, mc_configuration::l_current_min, mc_configuration::l_current_min_scale, mc_configuration::l_erpm_start, mc_configuration::l_in_current_max, mc_configuration::l_in_current_min, mc_configuration::l_max_duty, mc_configuration::l_max_erpm, mc_configuration::l_max_erpm_fbrake, mc_configuration::l_max_erpm_fbrake_cc, mc_configuration::l_max_vin, mc_configuration::l_min_duty, mc_configuration::l_min_erpm, mc_configuration::l_min_vin, mc_configuration::l_slow_abs_current, mc_configuration::l_temp_accel_dec, mc_configuration::l_temp_fet_end, mc_configuration::l_temp_fet_start, mc_configuration::l_temp_motor_end, mc_configuration::l_temp_motor_start, mc_configuration::l_watt_max, mc_configuration::l_watt_min, mc_configuration::m_bldc_f_sw_max, mc_configuration::m_bldc_f_sw_min, mc_configuration::m_current_backoff_gain, mc_configuration::m_dc_f_sw, mc_configuration::m_drv8301_oc_adj, mc_configuration::m_drv8301_oc_mode, mc_configuration::m_duty_ramp_step, mc_configuration::m_encoder_counts, mc_configuration::m_fault_stop_time_ms, mc_configuration::m_invert_direction, mc_configuration::m_ntc_motor_beta, mc_configuration::m_out_aux_mode, mc_configuration::m_sensor_port_mode, mc_configuration::motor_type, mc_configuration::p_pid_ang_div, mc_configuration::p_pid_kd, mc_configuration::p_pid_kd_filter, mc_configuration::p_pid_ki, mc_configuration::p_pid_kp, mc_configuration::pwm_mode, receivePacket(), mc_configuration::s_pid_allow_braking, mc_configuration::s_pid_kd, mc_configuration::s_pid_kd_filter, mc_configuration::s_pid_ki, mc_configuration::s_pid_kp, mc_configuration::s_pid_min_erpm, sendPacket(), mc_configuration::sensor_mode, mc_configuration::si_battery_ah, mc_configuration::si_battery_cells, mc_configuration::si_battery_type, mc_configuration::si_gear_ratio, mc_configuration::si_motor_poles, mc_configuration::si_wheel_diameter, mc_configuration::signature, mc_configuration::sl_bemf_coupling_k, mc_configuration::sl_cycle_int_limit, mc_configuration::sl_cycle_int_rpm_br, mc_configuration::sl_max_fullbreak_current_dir_change, mc_configuration::sl_min_erpm, mc_configuration::sl_min_erpm_cycle_int_limit, mc_configuration::sl_phase_advance_at_br, VescUtility::utility_get_float32_auto(), VescUtility::utility_get_int16(), VescUtility::utility_get_int32(), and VescUtility::utility_get_uint32().

◆ getMotorTemperature()

float Vesc::getMotorTemperature ( )

get motor temperature

Returns
float temperature

Definition at line 222 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float16().

◆ getPidPosNow()

float Vesc::getPidPosNow ( )

get pid pos now

Returns
float pid pos now

Definition at line 477 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getRealtimeValues()

◆ getRealtimeValuesSelective()

◆ getResetAvgId()

float Vesc::getResetAvgId ( )

get reset average id

Returns
float reset average id

Definition at line 273 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getResetAvgIq()

float Vesc::getResetAvgIq ( )

get reset average iq

Returns
float reset average iq

Definition at line 290 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getResetAvgVd()

float Vesc::getResetAvgVd ( )

get reset average vd

Returns
float reset average vd

Definition at line 530 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getResetAvgVq()

float Vesc::getResetAvgVq ( )

get reset average vq

Returns
float reset average vq

Definition at line 547 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getRPM()

float Vesc::getRPM ( )

get rpm

Returns
float rpm

Definition at line 324 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getTachometerAbsValue()

int32_t Vesc::getTachometerAbsValue ( )

get tachometer abs value

Returns
int32_t tachometer abs value

Definition at line 444 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_int32().

◆ getTachometerValue()

int32_t Vesc::getTachometerValue ( )

get tachometer value

Returns
int32_t tachometer value

Definition at line 427 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_int32().

◆ getWattHours()

float Vesc::getWattHours ( )

get watt hours

Returns
float watt hours

Definition at line 393 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ getWattHoursCharged()

float Vesc::getWattHoursCharged ( )

get watt hours charged

Returns
float watt hours charged

Definition at line 410 of file vesc.cpp.

References getRealtimeValuesSelective(), and VescUtility::utility_get_float32().

◆ init()

void Vesc::init ( HardwareSerial *  uart,
HardwareSerial *  debug 
)

init vesc interface

Parameters
uart
debug

Definition at line 31 of file vesc.cpp.

References debugPort, and uartPort.

◆ receivePacket()

bool Vesc::receivePacket ( unsigned char *  data)
private

helper method to receive packet

Parameters
datastore received byte array
Returns
true if reading was sucessfull
false if reading gone wrong

Definition at line 593 of file vesc.cpp.

References VescPacket::receive_packet(), and uartPort.

Referenced by getFirmwareVersion(), getMotorConfiguration(), getRealtimeValues(), and getRealtimeValuesSelective().

◆ sendPacket()

void Vesc::sendPacket ( unsigned char *  data,
unsigned int  len 
)
private

helper method to send packet

Parameters
datato send
lenof byte array

Definition at line 581 of file vesc.cpp.

References VescPacket::send_packet(), and uartPort.

Referenced by getFirmwareVersion(), getMotorConfiguration(), getRealtimeValues(), getRealtimeValuesSelective(), setBrakeCurrent(), setCurrent(), setDuty(), setHandbrake(), setPosition(), and setRPM().

◆ setBrakeCurrent()

void Vesc::setBrakeCurrent ( float  current)

set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncated if exeeds max motor current!

Parameters
current

Definition at line 72 of file vesc.cpp.

References COMM_SET_CURRENT_BRAKE, sendPacket(), and VescUtility::utility_append_int32().

◆ setCurrent()

void Vesc::setCurrent ( float  current)

set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncated if exeeds max motor current!

Parameters
current

Definition at line 57 of file vesc.cpp.

References COMM_SET_CURRENT, sendPacket(), and VescUtility::utility_append_int32().

◆ setDuty()

void Vesc::setDuty ( float  duty)

set duty cycle range 0.0% - 1.0%

Parameters
duty

Definition at line 42 of file vesc.cpp.

References COMM_SET_DUTY, sendPacket(), and VescUtility::utility_append_int32().

◆ setHandbrake()

void Vesc::setHandbrake ( float  current)

set handbreak 0 - MAX

Parameters
current

Definition at line 114 of file vesc.cpp.

References COMM_SET_HANDBRAKE, sendPacket(), and VescUtility::utility_append_float32().

◆ setPosition()

void Vesc::setPosition ( float  position)

set rpm 0 - MAX

Parameters
position

Definition at line 100 of file vesc.cpp.

References COMM_SET_POS, sendPacket(), and VescUtility::utility_append_int32().

◆ setRPM()

void Vesc::setRPM ( int32_t  rpm)

set rpm to set 0 - MAX

Parameters
rpm

Definition at line 86 of file vesc.cpp.

References COMM_SET_CURRENT_BRAKE, sendPacket(), and VescUtility::utility_append_int32().

Member Data Documentation

◆ debugPort

HardwareSerial* Vesc::debugPort = NULL
private

Definition at line 66 of file vesc.h.

Referenced by init().

◆ uartPort

HardwareSerial* Vesc::uartPort = NULL
private

Definition at line 65 of file vesc.h.

Referenced by init(), receivePacket(), and sendPacket().


The documentation for this class was generated from the following files: