Arduino_VESC_Library
vesc.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of the arduino vesc library (https://github.com/arduino_vesc)
3  *
4  * Copyright (c) 2019 Gianmarco Vitelli
5  *
6  * This program is free software: you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation, version 3.
9  *
10  * This program is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  * General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  */
18 #include "vesc.h"
19 #include "vesc_utility.h"
20 
22 {
23 }
24 
31 void Vesc::init(HardwareSerial *uart, HardwareSerial *debug)
32 {
33  uartPort = uart;
34  debugPort = debug;
35 }
36 
42 void Vesc::setDuty(float duty)
43 {
44  uint8_t send_buffer[5];
45  int32_t ind = 0;
46  send_buffer[ind++] = COMM_SET_DUTY;
47  VescUtility::utility_append_int32(send_buffer, (int32_t)(duty * 100000), &ind);
48  sendPacket(send_buffer, ind);
49 }
50 
57 void Vesc::setCurrent(float current)
58 {
59  uint8_t send_buffer[5];
60  int32_t ind = 0;
61  send_buffer[ind++] = COMM_SET_CURRENT;
62  VescUtility::utility_append_int32(send_buffer, (int32_t)(current * 1000), &ind);
63  sendPacket(send_buffer, ind);
64 }
65 
72 void Vesc::setBrakeCurrent(float current)
73 {
74  uint8_t send_buffer[5];
75  int32_t ind = 0;
76  send_buffer[ind++] = COMM_SET_CURRENT_BRAKE;
77  VescUtility::utility_append_int32(send_buffer, (int32_t)(current * 1000), &ind);
78  sendPacket(send_buffer, ind);
79 }
80 
86 void Vesc::setRPM(int32_t rpm)
87 {
88  uint8_t send_buffer[5];
89  int32_t ind = 0;
90  send_buffer[ind++] = COMM_SET_CURRENT_BRAKE;
91  VescUtility::utility_append_int32(send_buffer, rpm, &ind);
92  sendPacket(send_buffer, ind);
93 }
94 
100 void Vesc::setPosition(float position)
101 {
102  uint8_t send_buffer[5];
103  int32_t ind = 0;
104  send_buffer[ind++] = COMM_SET_POS;
105  VescUtility::utility_append_int32(send_buffer, (int32_t)(position * 1000000), &ind);
106  sendPacket(send_buffer, ind);
107 }
108 
114 void Vesc::setHandbrake(float current)
115 {
116  uint8_t send_buffer[5];
117  int32_t ind = 0;
118  send_buffer[ind++] = COMM_SET_HANDBRAKE;
119  VescUtility::utility_append_float32(send_buffer, current, 1e3, &ind);
120  sendPacket(send_buffer, ind);
121 }
122 
129 {
130  vesc_version version;
131  uint8_t send_buffer[5];
132  uint8_t receive_buffer[50];
133  int32_t ind = 0;
134  send_buffer[ind++] = COMM_FW_VERSION;
135  sendPacket(send_buffer, ind);
136 
137  if (receivePacket(receive_buffer) && receive_buffer[0] == COMM_FW_VERSION)
138  {
139  version.major = receive_buffer[ind++];
140  version.minor = receive_buffer[ind++];
141 
142  uint8_t *index_pointer = (uint8_t*)strchr((char*)receive_buffer + ind, '\0');
143  int index = index_pointer - receive_buffer + ind;
144  memcpy(version.hw_name, receive_buffer + ind, index);
145  ind += index;
146  memcpy(version.stm32_uid, receive_buffer + ind, 12);
147  ind += 12;
148 
149  version.pairing_done = receive_buffer[ind++];
150  }
151 
152  return version;
153 }
154 
161 {
162  vesc_values values;
163  uint8_t send_buffer[1];
164  uint8_t receive_buffer[600];
165  int32_t ind = 0;
166  send_buffer[ind++] = COMM_GET_VALUES;
167  sendPacket(send_buffer, ind);
168 
169  if (receivePacket(receive_buffer) && receive_buffer[0] == COMM_GET_VALUES)
170  {
171  ind = 1;
172  values.fet_temp = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
173  values.motor_temp = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
174  values.avg_motor_current = VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
175  values.avg_input_current = VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
176  values.reset_avg_id = VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
177  values.reset_avg_iq = VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
178  values.duty_cycle_now = VescUtility::utility_get_float16(receive_buffer, 1e3, &ind);
179  values.rpm = VescUtility::utility_get_float32(receive_buffer, 1e0, &ind);
180  values.input_voltage = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
181  values.amp_hours = VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
182  values.amp_hours_charged = VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
183  values.watt_hours = VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
184  values.watt_hours_charged = VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
185  values.tachometer_value = VescUtility::utility_get_int32(receive_buffer, &ind);
186  values.tachometer_abs_value = VescUtility::utility_get_int32(receive_buffer, &ind);
187  values.fault = receive_buffer[ind++];
188  values.pid_pos_now = VescUtility::utility_get_float32(receive_buffer, 1e6, &ind);
189  values.controller_id = receive_buffer[ind++];
190  values.mos1_temp = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
191  values.mos2_temp = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
192  values.mos3_temp = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
193  values.reset_avg_vd = VescUtility::utility_get_float32(receive_buffer, 1e3, &ind);
194  values.reset_avg_vq = VescUtility::utility_get_float32(receive_buffer, 1e3, &ind);
195  }
196 
197  return values;
198 }
199 
206 {
207  uint8_t receive_buffer[10];
208  int32_t ind = 5;
209  if (getRealtimeValuesSelective(receive_buffer, 0))
210  {
211  return VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
212  }
213 
214  return 0;
215 }
216 
223 {
224  uint8_t receive_buffer[10];
225  int32_t ind = 5;
226  if (getRealtimeValuesSelective(receive_buffer, 1))
227  {
228  return VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
229  }
230 
231  return 0;
232 }
233 
240 {
241  uint8_t receive_buffer[10];
242  int32_t ind = 5;
243  if (getRealtimeValuesSelective(receive_buffer, 2))
244  {
245  return VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
246  }
247 
248  return 0;
249 }
250 
257 {
258  uint8_t receive_buffer[10];
259  int32_t ind = 5;
260  if (getRealtimeValuesSelective(receive_buffer, 3))
261  {
262  return VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
263  }
264 
265  return 0;
266 }
267 
274 {
275  uint8_t receive_buffer[10];
276  int32_t ind = 5;
277  if (getRealtimeValuesSelective(receive_buffer, 4))
278  {
279  return VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
280  }
281 
282  return 0;
283 }
284 
291 {
292  uint8_t receive_buffer[10];
293  int32_t ind = 5;
294  if (getRealtimeValuesSelective(receive_buffer, 5))
295  {
296  return VescUtility::utility_get_float32(receive_buffer, 1e2, &ind);
297  }
298 
299  return 0;
300 }
301 
308 {
309  uint8_t receive_buffer[10];
310  int32_t ind = 5;
311  if (getRealtimeValuesSelective(receive_buffer, 6))
312  {
313  return VescUtility::utility_get_float16(receive_buffer, 1e3, &ind);
314  }
315 
316  return 0;
317 }
318 
325 {
326  uint8_t receive_buffer[10];
327  int32_t ind = 5;
328  if (getRealtimeValuesSelective(receive_buffer, 7))
329  {
330  return VescUtility::utility_get_float32(receive_buffer, 1e0, &ind);
331  }
332 
333  return 0;
334 }
335 
342 {
343  uint8_t receive_buffer[6];
344  int32_t ind = 5;
345  if (getRealtimeValuesSelective(receive_buffer, 8))
346  {
347  return VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
348  }
349 
350  return 0;
351 }
352 
353 
360 {
361  uint8_t receive_buffer[10];
362  int32_t ind = 5;
363  if (getRealtimeValuesSelective(receive_buffer, 9))
364  {
365  return VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
366  }
367 
368  return 0;
369 }
370 
377 {
378  uint8_t receive_buffer[10];
379  int32_t ind = 5;
380  if (getRealtimeValuesSelective(receive_buffer, 10))
381  {
382  return VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
383  }
384 
385  return 0;
386 }
387 
394 {
395  uint8_t receive_buffer[10];
396  int32_t ind = 5;
397  if (getRealtimeValuesSelective(receive_buffer, 11))
398  {
399  return VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
400  }
401 
402  return 0;
403 }
404 
411 {
412  uint8_t receive_buffer[10];
413  int32_t ind = 5;
414  if (getRealtimeValuesSelective(receive_buffer, 12))
415  {
416  return VescUtility::utility_get_float32(receive_buffer, 1e4, &ind);
417  }
418 
419  return 0;
420 }
421 
428 {
429  uint8_t receive_buffer[10];
430  int32_t ind = 5;
431  if (getRealtimeValuesSelective(receive_buffer, 13))
432  {
433  return VescUtility::utility_get_int32(receive_buffer, &ind);
434  }
435 
436  return 0;
437 }
438 
445 {
446  uint8_t receive_buffer[10];
447  int32_t ind = 5;
448  if (getRealtimeValuesSelective(receive_buffer, 14))
449  {
450  return VescUtility::utility_get_int32(receive_buffer, &ind);
451  }
452 
453  return 0;
454 }
455 
461 uint8_t Vesc::getFault()
462 {
463  uint8_t receive_buffer[10];
464  if (getRealtimeValuesSelective(receive_buffer, 15))
465  {
466  return receive_buffer[2];
467  }
468 
469  return 0;
470 }
471 
478 {
479  uint8_t receive_buffer[10];
480  int32_t ind = 5;
481  if (getRealtimeValuesSelective(receive_buffer, 16))
482  {
483  return VescUtility::utility_get_float32(receive_buffer, 1e6, &ind);
484  }
485 
486  return 0;
487 }
488 
495 {
496  uint8_t receive_buffer[10];
497  if (getRealtimeValuesSelective(receive_buffer, 17))
498  {
499  return receive_buffer[2];
500  }
501 
502  return 0;
503 }
504 
511 {
512  float values[3];
513  uint8_t receive_buffer[10];
514  if (getRealtimeValuesSelective(receive_buffer, 18))
515  {
516  int32_t ind = 5;
517  values[0] = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
518  values[1] = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
519  values[2] = VescUtility::utility_get_float16(receive_buffer, 1e1, &ind);
520  }
521 
522  return values;
523 }
524 
531 {
532  uint8_t receive_buffer[10];
533  int32_t ind = 5;
534  if (getRealtimeValuesSelective(receive_buffer, 19))
535  {
536  return VescUtility::utility_get_float32(receive_buffer, 1e3, &ind);
537  }
538 
539  return 0;
540 }
541 
548 {
549  uint8_t receive_buffer[10];
550  int32_t ind = 5;
551  if (getRealtimeValuesSelective(receive_buffer, 20))
552  {
553  return VescUtility::utility_get_float32(receive_buffer, 1e3, &ind);
554  }
555 
556  return 0;
557 }
558 
564 bool Vesc::getRealtimeValuesSelective(unsigned char *data, unsigned int index)
565 {
566  uint8_t send_buffer[6];
567  int32_t ind = 0;
568  send_buffer[ind++] = COMM_GET_VALUES_SELECTIVE;
569  VescUtility::utility_append_uint32(send_buffer, ((uint32_t)1 << index), &ind);
570  sendPacket(send_buffer, ind);
571 
572  return receivePacket(data) && data[0] == COMM_GET_VALUES_SELECTIVE;
573 }
574 
581 void Vesc::sendPacket(unsigned char *data, unsigned int len)
582 {
583  VescPacket::send_packet(uartPort, data, len);
584 }
585 
593 bool Vesc::receivePacket(unsigned char *data)
594 {
595  return VescPacket::receive_packet(uartPort, data);
596 }
597 
604  mc_configuration conf;
605  uint8_t receive_buffer[600];
606  uint8_t send_buffer[2];
607  int32_t ind = 0;
608  send_buffer[ind++] = COMM_GET_MCCONF;
609  sendPacket(send_buffer, ind);
610 
611  if (receivePacket(receive_buffer) && receive_buffer[0] == COMM_GET_MCCONF)
612  {
613  int32_t ind = 0;
614  conf.signature = VescUtility::utility_get_uint32(receive_buffer, &ind);
615  conf.pwm_mode = receive_buffer[ind++];
616  conf.comm_mode = receive_buffer[ind++];
617  conf.motor_type = receive_buffer[ind++];
618  conf.sensor_mode = receive_buffer[ind++];
619  conf.l_current_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
620  conf.l_current_min = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
621  conf.l_in_current_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
622  conf.l_in_current_min = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
623  conf.l_abs_current_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
624  conf.l_min_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
625  conf.l_max_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
626  conf.l_erpm_start = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
627  conf.l_max_erpm_fbrake = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
628  conf.l_max_erpm_fbrake_cc = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
629  conf.l_min_vin = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
630  conf.l_max_vin = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
631  conf.l_battery_cut_start = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
632  conf.l_battery_cut_end = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
633  conf.l_slow_abs_current = receive_buffer[ind++];
634  conf.l_temp_fet_start = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
635  conf.l_temp_fet_end = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
636  conf.l_temp_motor_start = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
637  conf.l_temp_motor_end = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
638  conf.l_temp_accel_dec = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
639  conf.l_min_duty = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
640  conf.l_max_duty = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
641  conf.l_watt_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
642  conf.l_watt_min = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
643  conf.l_current_max_scale = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
644  conf.l_current_min_scale = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
645  conf.sl_min_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
648  conf.sl_cycle_int_limit = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
650  conf.sl_cycle_int_rpm_br = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
651  conf.sl_bemf_coupling_k = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
652  conf.hall_table[0] = receive_buffer[ind++];
653  conf.hall_table[1] = receive_buffer[ind++];
654  conf.hall_table[2] = receive_buffer[ind++];
655  conf.hall_table[3] = receive_buffer[ind++];
656  conf.hall_table[4] = receive_buffer[ind++];
657  conf.hall_table[5] = receive_buffer[ind++];
658  conf.hall_table[6] = receive_buffer[ind++];
659  conf.hall_table[7] = receive_buffer[ind++];
660  conf.hall_sl_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
661  conf.foc_current_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
662  conf.foc_current_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
663  conf.foc_f_sw = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
664  conf.foc_dt_us = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
665  conf.foc_encoder_inverted = receive_buffer[ind++];
666  conf.foc_encoder_offset = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
667  conf.foc_encoder_ratio = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
668  conf.foc_encoder_sin_gain = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
669  conf.foc_encoder_cos_gain = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
673  conf.foc_sensor_mode = receive_buffer[ind++];
674  conf.foc_pll_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
675  conf.foc_pll_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
676  conf.foc_motor_l = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
677  conf.foc_motor_r = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
679  conf.foc_observer_gain = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
681  conf.foc_duty_dowmramp_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
682  conf.foc_duty_dowmramp_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
683  conf.foc_openloop_rpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
684  conf.foc_sl_openloop_hyst = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
685  conf.foc_sl_openloop_time = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
688  conf.foc_hall_table[0] = receive_buffer[ind++];
689  conf.foc_hall_table[1] = receive_buffer[ind++];
690  conf.foc_hall_table[2] = receive_buffer[ind++];
691  conf.foc_hall_table[3] = receive_buffer[ind++];
692  conf.foc_hall_table[4] = receive_buffer[ind++];
693  conf.foc_hall_table[5] = receive_buffer[ind++];
694  conf.foc_hall_table[6] = receive_buffer[ind++];
695  conf.foc_hall_table[7] = receive_buffer[ind++];
696  conf.foc_sl_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
697  conf.foc_sample_v0_v7 = receive_buffer[ind++];
698  conf.foc_sample_high_current = receive_buffer[ind++];
699  conf.foc_sat_comp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
700  conf.foc_temp_comp = receive_buffer[ind++];
703  conf.gpd_buffer_notify_left = VescUtility::utility_get_int16(receive_buffer, &ind);
704  conf.gpd_buffer_interpol = VescUtility::utility_get_int16(receive_buffer, &ind);
706  conf.gpd_current_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
707  conf.gpd_current_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
708  conf.s_pid_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
709  conf.s_pid_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
710  conf.s_pid_kd = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
711  conf.s_pid_kd_filter = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
712  conf.s_pid_min_erpm = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
713  conf.s_pid_allow_braking = receive_buffer[ind++];
714  conf.p_pid_kp = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
715  conf.p_pid_ki = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
716  conf.p_pid_kd = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
717  conf.p_pid_kd_filter = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
718  conf.p_pid_ang_div = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
720  conf.cc_min_current = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
721  conf.cc_gain = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
722  conf.cc_ramp_step_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
723  conf.m_fault_stop_time_ms = VescUtility::utility_get_int32(receive_buffer, &ind);
724  conf.m_duty_ramp_step = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
726  conf.m_encoder_counts = VescUtility::utility_get_uint32(receive_buffer, &ind);
727  conf.m_sensor_port_mode = receive_buffer[ind++];
728  conf.m_invert_direction = receive_buffer[ind++];
729  conf.m_drv8301_oc_mode = receive_buffer[ind++];
730  conf.m_drv8301_oc_adj = receive_buffer[ind++];
731  conf.m_bldc_f_sw_min = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
732  conf.m_bldc_f_sw_max = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
733  conf.m_dc_f_sw = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
734  conf.m_ntc_motor_beta = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
735  conf.m_out_aux_mode = receive_buffer[ind++];
736  conf.si_motor_poles = receive_buffer[ind++];
737  conf.si_gear_ratio = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
738  conf.si_wheel_diameter = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
739  conf.si_battery_type = receive_buffer[ind++];
740  conf.si_battery_cells = receive_buffer[ind++];
741  conf.si_battery_ah = VescUtility::utility_get_float32_auto(receive_buffer, &ind);
742  }
743 
744  return conf;
745 }
mc_configuration::l_min_duty
float l_min_duty
Definition: vesc_types.h:81
Vesc::setHandbrake
void setHandbrake(float current)
set handbreak 0 - MAX
Definition: vesc.cpp:114
Vesc::getPidPosNow
float getPidPosNow()
get pid pos now
Definition: vesc.cpp:477
VescUtility::utility_append_int32
static void utility_append_int32(uint8_t *buffer, int32_t number, int32_t *index)
append int32 to buffer
Definition: vesc_utility.cpp:54
mc_configuration::l_watt_max
float l_watt_max
Definition: vesc_types.h:83
mc_configuration::comm_mode
uint8_t comm_mode
Definition: vesc_types.h:57
mc_configuration::foc_encoder_inverted
bool foc_encoder_inverted
Definition: vesc_types.h:111
VescUtility::utility_get_float16
static float utility_get_float16(const uint8_t *buffer, float scale, int32_t *index)
get float16 from buffer
Definition: vesc_utility.cpp:193
vesc_values::motor_temp
float motor_temp
Definition: vesc_types.h:29
mc_configuration::sl_min_erpm_cycle_int_limit
float sl_min_erpm_cycle_int_limit
Definition: vesc_types.h:96
mc_configuration::l_battery_cut_start
float l_battery_cut_start
Definition: vesc_types.h:73
vesc_utility.h
Vesc::getRealtimeValues
vesc_values getRealtimeValues()
get real time values
Definition: vesc.cpp:160
mc_configuration::p_pid_ang_div
float p_pid_ang_div
Definition: vesc_types.h:159
mc_configuration::foc_sl_openloop_time
float foc_sl_openloop_time
Definition: vesc_types.h:129
vesc_values::tachometer_value
int32_t tachometer_value
Definition: vesc_types.h:41
mc_configuration::p_pid_kd_filter
float p_pid_kd_filter
Definition: vesc_types.h:158
vesc_values::input_voltage
float input_voltage
Definition: vesc_types.h:36
mc_configuration::m_current_backoff_gain
float m_current_backoff_gain
Definition: vesc_types.h:168
mc_configuration::si_gear_ratio
float si_gear_ratio
Definition: vesc_types.h:181
mc_configuration::l_in_current_min
float l_in_current_min
Definition: vesc_types.h:64
VescUtility::utility_get_uint32
static uint32_t utility_get_uint32(const uint8_t *buffer, int32_t *index)
get uint32_t from buffer
Definition: vesc_utility.cpp:176
mc_configuration::m_bldc_f_sw_min
float m_bldc_f_sw_min
Definition: vesc_types.h:174
mc_configuration::si_battery_type
uint8_t si_battery_type
Definition: vesc_types.h:183
mc_configuration::foc_sat_comp
float foc_sat_comp
Definition: vesc_types.h:137
mc_configuration::foc_current_filter_const
float foc_current_filter_const
Definition: vesc_types.h:140
Vesc::getMosfetsTemperature
float * getMosfetsTemperature()
get mosfets temperature
Definition: vesc.cpp:510
Vesc::getAmpHours
float getAmpHours()
get amp hours
Definition: vesc.cpp:359
mc_configuration::pwm_mode
uint8_t pwm_mode
Definition: vesc_types.h:56
Vesc::setRPM
void setRPM(int32_t rpm)
set rpm to set 0 - MAX
Definition: vesc.cpp:86
Vesc::getTachometerAbsValue
int32_t getTachometerAbsValue()
get tachometer abs value
Definition: vesc.cpp:444
Vesc::setBrakeCurrent
void setBrakeCurrent(float current)
set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncat...
Definition: vesc.cpp:72
mc_configuration::foc_encoder_sin_offset
float foc_encoder_sin_offset
Definition: vesc_types.h:113
mc_configuration::foc_pll_ki
float foc_pll_ki
Definition: vesc_types.h:124
mc_configuration::foc_encoder_cos_offset
float foc_encoder_cos_offset
Definition: vesc_types.h:115
mc_configuration::l_slow_abs_current
bool l_slow_abs_current
Definition: vesc_types.h:75
vesc_values::watt_hours_charged
float watt_hours_charged
Definition: vesc_types.h:40
mc_configuration::motor_type
uint8_t motor_type
Definition: vesc_types.h:58
mc_configuration::s_pid_kp
float s_pid_kp
Definition: vesc_types.h:148
mc_configuration::m_drv8301_oc_mode
uint8_t m_drv8301_oc_mode
Definition: vesc_types.h:172
Vesc::uartPort
HardwareSerial * uartPort
Definition: vesc.h:65
mc_configuration::l_battery_cut_end
float l_battery_cut_end
Definition: vesc_types.h:74
mc_configuration::sl_bemf_coupling_k
float sl_bemf_coupling_k
Definition: vesc_types.h:101
mc_configuration::l_watt_min
float l_watt_min
Definition: vesc_types.h:84
mc_configuration::l_max_duty
float l_max_duty
Definition: vesc_types.h:82
VescUtility::utility_get_int32
static int32_t utility_get_int32(const uint8_t *buffer, int32_t *index)
get int32_t from buffer
Definition: vesc_utility.cpp:160
Vesc::init
void init(HardwareSerial *uartPort, HardwareSerial *debugPort)
init vesc interface
Definition: vesc.cpp:31
mc_configuration::s_pid_kd_filter
float s_pid_kd_filter
Definition: vesc_types.h:151
mc_configuration::si_wheel_diameter
float si_wheel_diameter
Definition: vesc_types.h:182
Vesc::getResetAvgVd
float getResetAvgVd()
get reset average vd
Definition: vesc.cpp:530
mc_configuration::l_temp_fet_end
float l_temp_fet_end
Definition: vesc_types.h:77
mc_configuration::foc_duty_dowmramp_kp
float foc_duty_dowmramp_kp
Definition: vesc_types.h:125
mc_configuration::s_pid_min_erpm
float s_pid_min_erpm
Definition: vesc_types.h:152
mc_configuration::foc_encoder_sin_gain
float foc_encoder_sin_gain
Definition: vesc_types.h:114
vesc_values::fet_temp
float fet_temp
Definition: vesc_types.h:28
mc_configuration::sl_phase_advance_at_br
float sl_phase_advance_at_br
Definition: vesc_types.h:99
Vesc::getResetAvgIq
float getResetAvgIq()
get reset average iq
Definition: vesc.cpp:290
mc_configuration::foc_pll_kp
float foc_pll_kp
Definition: vesc_types.h:123
Vesc::receivePacket
bool receivePacket(unsigned char *data)
helper method to receive packet
Definition: vesc.cpp:593
mc_configuration::foc_encoder_offset
float foc_encoder_offset
Definition: vesc_types.h:110
mc_configuration::l_abs_current_max
float l_abs_current_max
Definition: vesc_types.h:65
mc_configuration::foc_temp_comp_base_temp
float foc_temp_comp_base_temp
Definition: vesc_types.h:139
Vesc::getaAmpHoursCharged
float getaAmpHoursCharged()
get amp hours charged
Definition: vesc.cpp:376
Vesc::setCurrent
void setCurrent(float current)
set current 0 - MAX this value will passed directly to mcpwn / mcfoc / mcbldc and will be not truncat...
Definition: vesc.cpp:57
mc_configuration::cc_startup_boost_duty
float cc_startup_boost_duty
Definition: vesc_types.h:161
mc_configuration::l_temp_accel_dec
float l_temp_accel_dec
Definition: vesc_types.h:80
mc_configuration::m_ntc_motor_beta
float m_ntc_motor_beta
Definition: vesc_types.h:177
Vesc::getInputVoltage
float getInputVoltage()
get input voltage
Definition: vesc.cpp:341
mc_configuration::si_motor_poles
uint8_t si_motor_poles
Definition: vesc_types.h:180
mc_configuration::l_max_erpm
float l_max_erpm
Definition: vesc_types.h:67
Vesc::getMotorConfiguration
mc_configuration getMotorConfiguration()
get motor configuration
Definition: vesc.cpp:603
vesc_values::reset_avg_vd
float reset_avg_vd
Definition: vesc_types.h:49
Vesc::getFetTemperature
float getFetTemperature()
get MosFet temperature
Definition: vesc.cpp:205
mc_configuration::gpd_buffer_notify_left
int gpd_buffer_notify_left
Definition: vesc_types.h:142
vesc_version::major
uint8_t major
Definition: vesc_types.h:20
vesc_values::fault
float fault
Definition: vesc_types.h:43
mc_configuration::gpd_current_kp
float gpd_current_kp
Definition: vesc_types.h:145
vesc_values::watt_hours
float watt_hours
Definition: vesc_types.h:39
mc_configuration::foc_motor_r
float foc_motor_r
Definition: vesc_types.h:119
vesc.h
mc_configuration::foc_duty_dowmramp_ki
float foc_duty_dowmramp_ki
Definition: vesc_types.h:126
mc_configuration::cc_ramp_step_max
float cc_ramp_step_max
Definition: vesc_types.h:164
COMM_SET_POS
Definition: vesc_types.h:198
mc_configuration::l_max_vin
float l_max_vin
Definition: vesc_types.h:72
mc_configuration::foc_observer_gain
float foc_observer_gain
Definition: vesc_types.h:121
Vesc::Vesc
Vesc(void)
Definition: vesc.cpp:21
mc_configuration::foc_sl_d_current_duty
float foc_sl_d_current_duty
Definition: vesc_types.h:130
Vesc::getRealtimeValuesSelective
bool getRealtimeValuesSelective(unsigned char *data, unsigned int index)
helper method to retrieve single values from vesc
Definition: vesc.cpp:564
mc_configuration::foc_sample_v0_v7
bool foc_sample_v0_v7
Definition: vesc_types.h:135
Vesc::getFault
uint8_t getFault()
get fault
Definition: vesc.cpp:461
vesc_values::amp_hours
float amp_hours
Definition: vesc_types.h:37
mc_configuration::s_pid_allow_braking
bool s_pid_allow_braking
Definition: vesc_types.h:153
mc_configuration::foc_observer_gain_slow
float foc_observer_gain_slow
Definition: vesc_types.h:122
mc_configuration::s_pid_kd
float s_pid_kd
Definition: vesc_types.h:150
mc_configuration::cc_min_current
float cc_min_current
Definition: vesc_types.h:162
mc_configuration::l_temp_fet_start
float l_temp_fet_start
Definition: vesc_types.h:76
Vesc::getAvgInputCurrent
float getAvgInputCurrent()
get average input current
Definition: vesc.cpp:256
mc_configuration::foc_openloop_rpm
float foc_openloop_rpm
Definition: vesc_types.h:127
mc_configuration::m_sensor_port_mode
uint8_t m_sensor_port_mode
Definition: vesc_types.h:170
mc_configuration::foc_temp_comp
bool foc_temp_comp
Definition: vesc_types.h:138
mc_configuration::foc_encoder_sincos_filter_constant
float foc_encoder_sincos_filter_constant
Definition: vesc_types.h:117
Vesc::getAvgMotorCurrent
float getAvgMotorCurrent()
get average motor current
Definition: vesc.cpp:239
Vesc::debugPort
HardwareSerial * debugPort
Definition: vesc.h:66
mc_configuration::m_invert_direction
bool m_invert_direction
Definition: vesc_types.h:171
Vesc::sendPacket
void sendPacket(unsigned char *data, unsigned int len)
helper method to send packet
Definition: vesc.cpp:581
mc_configuration::m_out_aux_mode
uint8_t m_out_aux_mode
Definition: vesc_types.h:178
vesc_values::reset_avg_id
float reset_avg_id
Definition: vesc_types.h:32
mc_configuration::sl_cycle_int_limit
float sl_cycle_int_limit
Definition: vesc_types.h:98
VescUtility::utility_get_float32_auto
static float utility_get_float32_auto(const uint8_t *buffer, int32_t *index)
get float32 from buffer auto scale
Definition: vesc_utility.cpp:216
mc_configuration::l_temp_motor_end
float l_temp_motor_end
Definition: vesc_types.h:79
VescPacket::send_packet
static void send_packet(HardwareSerial *port, unsigned char *data, unsigned int len)
send packet to vesc
Definition: vesc_packet.cpp:30
mc_configuration::m_encoder_counts
uint32_t m_encoder_counts
Definition: vesc_types.h:169
COMM_SET_HANDBRAKE
Definition: vesc_types.h:199
vesc_version::pairing_done
bool pairing_done
Definition: vesc_types.h:24
mc_configuration::si_battery_cells
int si_battery_cells
Definition: vesc_types.h:184
mc_configuration::foc_sl_openloop_hyst
float foc_sl_openloop_hyst
Definition: vesc_types.h:128
mc_configuration::signature
uint32_t signature
Definition: vesc_types.h:54
vesc_values::mos3_temp
float mos3_temp
Definition: vesc_types.h:48
VescUtility::utility_get_float32
static float utility_get_float32(const uint8_t *buffer, float scale, int32_t *index)
get float32 from buffer
Definition: vesc_utility.cpp:205
mc_configuration::gpd_current_filter_const
float gpd_current_filter_const
Definition: vesc_types.h:144
mc_configuration::m_duty_ramp_step
float m_duty_ramp_step
Definition: vesc_types.h:167
vesc_values::reset_avg_iq
float reset_avg_iq
Definition: vesc_types.h:33
mc_configuration::l_current_min_scale
float l_current_min_scale
Definition: vesc_types.h:86
COMM_GET_VALUES_SELECTIVE
Definition: vesc_types.h:239
mc_configuration::foc_encoder_ratio
float foc_encoder_ratio
Definition: vesc_types.h:112
COMM_SET_DUTY
Definition: vesc_types.h:194
mc_configuration::foc_dt_us
float foc_dt_us
Definition: vesc_types.h:109
COMM_GET_VALUES
Definition: vesc_types.h:193
mc_configuration::p_pid_ki
float p_pid_ki
Definition: vesc_types.h:156
mc_configuration::foc_motor_l
float foc_motor_l
Definition: vesc_types.h:118
COMM_FW_VERSION
Definition: vesc_types.h:189
mc_configuration::foc_sl_erpm
float foc_sl_erpm
Definition: vesc_types.h:134
mc_configuration::cc_gain
float cc_gain
Definition: vesc_types.h:163
Vesc::getControllerId
uint8_t getControllerId()
get controller id
Definition: vesc.cpp:494
vesc_version::minor
uint8_t minor
Definition: vesc_types.h:21
VescUtility::utility_append_float32
static void utility_append_float32(uint8_t *buffer, float number, float scale, int32_t *index)
append float32 to buffer
Definition: vesc_utility.cpp:95
COMM_SET_CURRENT_BRAKE
Definition: vesc_types.h:196
mc_configuration::hall_sl_erpm
float hall_sl_erpm
Definition: vesc_types.h:104
mc_configuration::l_current_max_scale
float l_current_max_scale
Definition: vesc_types.h:85
mc_configuration::foc_hall_table
uint8_t foc_hall_table[8]
Definition: vesc_types.h:133
vesc_values::mos1_temp
float mos1_temp
Definition: vesc_types.h:46
mc_configuration::l_current_max
float l_current_max
Definition: vesc_types.h:61
mc_configuration::p_pid_kd
float p_pid_kd
Definition: vesc_types.h:157
vesc_values::duty_cycle_now
float duty_cycle_now
Definition: vesc_types.h:34
mc_configuration::foc_current_ki
float foc_current_ki
Definition: vesc_types.h:107
vesc_values::rpm
float rpm
Definition: vesc_types.h:35
vesc_version
Definition: vesc_types.h:19
VescUtility::utility_append_uint32
static void utility_append_uint32(uint8_t *buffer, uint32_t number, int32_t *index)
append uint32 to buffer
Definition: vesc_utility.cpp:68
mc_configuration::l_min_erpm
float l_min_erpm
Definition: vesc_types.h:66
vesc_version::stm32_uid
uint8_t stm32_uid[12]
Definition: vesc_types.h:23
Vesc::getWattHoursCharged
float getWattHoursCharged()
get watt hours charged
Definition: vesc.cpp:410
mc_configuration::m_drv8301_oc_adj
int m_drv8301_oc_adj
Definition: vesc_types.h:173
mc_configuration::foc_sensor_mode
uint8_t foc_sensor_mode
Definition: vesc_types.h:132
Vesc::getWattHours
float getWattHours()
get watt hours
Definition: vesc.cpp:393
mc_configuration::foc_motor_flux_linkage
float foc_motor_flux_linkage
Definition: vesc_types.h:120
VescPacket::receive_packet
static bool receive_packet(HardwareSerial *port, unsigned char *data)
receive packet from vesc
Definition: vesc_packet.cpp:80
mc_configuration::hall_table
int8_t hall_table[8]
Definition: vesc_types.h:103
Vesc::setPosition
void setPosition(float position)
set rpm 0 - MAX
Definition: vesc.cpp:100
mc_configuration::m_fault_stop_time_ms
int32_t m_fault_stop_time_ms
Definition: vesc_types.h:166
mc_configuration::p_pid_kp
float p_pid_kp
Definition: vesc_types.h:155
vesc_values::tachometer_abs_value
int32_t tachometer_abs_value
Definition: vesc_types.h:42
mc_configuration::l_max_erpm_fbrake
float l_max_erpm_fbrake
Definition: vesc_types.h:69
mc_configuration::s_pid_ki
float s_pid_ki
Definition: vesc_types.h:149
mc_configuration::sl_cycle_int_rpm_br
float sl_cycle_int_rpm_br
Definition: vesc_types.h:100
mc_configuration::sl_min_erpm
float sl_min_erpm
Definition: vesc_types.h:95
mc_configuration::sensor_mode
uint8_t sensor_mode
Definition: vesc_types.h:59
vesc_values::mos2_temp
float mos2_temp
Definition: vesc_types.h:47
vesc_values::avg_motor_current
float avg_motor_current
Definition: vesc_types.h:30
vesc_values::pid_pos_now
float pid_pos_now
Definition: vesc_types.h:44
mc_configuration::foc_current_kp
float foc_current_kp
Definition: vesc_types.h:106
mc_configuration::foc_sample_high_current
bool foc_sample_high_current
Definition: vesc_types.h:136
vesc_values::reset_avg_vq
float reset_avg_vq
Definition: vesc_types.h:50
Vesc::setDuty
void setDuty(float duty)
set duty cycle range 0.0% - 1.0%
Definition: vesc.cpp:42
mc_configuration::l_erpm_start
float l_erpm_start
Definition: vesc_types.h:68
COMM_GET_MCCONF
Definition: vesc_types.h:203
mc_configuration::foc_sl_d_current_factor
float foc_sl_d_current_factor
Definition: vesc_types.h:131
VescUtility::utility_get_int16
static int16_t utility_get_int16(const uint8_t *buffer, int32_t *index)
get int16 from buffer
Definition: vesc_utility.cpp:132
mc_configuration::m_bldc_f_sw_max
float m_bldc_f_sw_max
Definition: vesc_types.h:175
vesc_version::hw_name
char hw_name[20]
Definition: vesc_types.h:22
vesc_values::avg_input_current
float avg_input_current
Definition: vesc_types.h:31
Vesc::getDutyCycleNow
float getDutyCycleNow()
get duty cycle now
Definition: vesc.cpp:307
Vesc::getRPM
float getRPM()
get rpm
Definition: vesc.cpp:324
mc_configuration::m_dc_f_sw
float m_dc_f_sw
Definition: vesc_types.h:176
mc_configuration::gpd_current_ki
float gpd_current_ki
Definition: vesc_types.h:146
Vesc::getFirmwareVersion
vesc_version getFirmwareVersion()
get firmware version
Definition: vesc.cpp:128
vesc_values::controller_id
uint8_t controller_id
Definition: vesc_types.h:45
mc_configuration::gpd_buffer_interpol
int gpd_buffer_interpol
Definition: vesc_types.h:143
mc_configuration::si_battery_ah
float si_battery_ah
Definition: vesc_types.h:185
vesc_values::amp_hours_charged
float amp_hours_charged
Definition: vesc_types.h:38
mc_configuration::foc_f_sw
float foc_f_sw
Definition: vesc_types.h:108
mc_configuration::sl_max_fullbreak_current_dir_change
float sl_max_fullbreak_current_dir_change
Definition: vesc_types.h:97
Vesc::getResetAvgId
float getResetAvgId()
get reset average id
Definition: vesc.cpp:273
Vesc::getResetAvgVq
float getResetAvgVq()
get reset average vq
Definition: vesc.cpp:547
mc_configuration::l_min_vin
float l_min_vin
Definition: vesc_types.h:71
vesc_values
Definition: vesc_types.h:27
mc_configuration
Definition: vesc_types.h:53
mc_configuration::l_temp_motor_start
float l_temp_motor_start
Definition: vesc_types.h:78
mc_configuration::l_max_erpm_fbrake_cc
float l_max_erpm_fbrake_cc
Definition: vesc_types.h:70
COMM_SET_CURRENT
Definition: vesc_types.h:195
mc_configuration::l_in_current_max
float l_in_current_max
Definition: vesc_types.h:63
mc_configuration::foc_encoder_cos_gain
float foc_encoder_cos_gain
Definition: vesc_types.h:116
mc_configuration::l_current_min
float l_current_min
Definition: vesc_types.h:62
Vesc::getMotorTemperature
float getMotorTemperature()
get motor temperature
Definition: vesc.cpp:222
Vesc::getTachometerValue
int32_t getTachometerValue()
get tachometer value
Definition: vesc.cpp:427