diff --git a/src/VescUartControl-VESC6/.gitignore b/src/VescUartControl-VESC6/.gitignore
new file mode 100644
index 0000000..8d97c8e
--- /dev/null
+++ b/src/VescUartControl-VESC6/.gitignore
@@ -0,0 +1,13 @@
+################################################################################
+# This .gitignore file was automatically created by Microsoft(R) Visual Studio.
+################################################################################
+
+*.d
+*.o
+*.hex
+*.elf
+*.xml
+*.buildinfo
+*.a
+*.suo
+/examples/VescTestGetTelemetry/__vm/.VescTestGetTelemetry.vsarduino.h
diff --git a/src/VescUartControl-VESC6/LICENSE.md b/src/VescUartControl-VESC6/LICENSE.md
new file mode 100644
index 0000000..a700de2
--- /dev/null
+++ b/src/VescUartControl-VESC6/LICENSE.md
@@ -0,0 +1,15 @@
+VescUartControl library
+Copyright 2015 - 2017 Andreas Chaitidis Andreas.Chaitidis@gmail.com
+
+This program is free software : you can redistribute it and / or modify
+it under the terms of the GNU General Public License as published by
+the Free Software Foundation, either version 3 of the License, or
+(at your option) any later version.
+
+This program is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.See the
+GNU General Public License for more details.
+
+You should have received a copy of the GNU General Public License
+along with this program.If not, see .
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/Readme.md b/src/VescUartControl-VESC6/Readme.md
new file mode 100644
index 0000000..3430172
--- /dev/null
+++ b/src/VescUartControl-VESC6/Readme.md
@@ -0,0 +1,48 @@
+#VescUartControl library
+
+Library for arduino to interface over UART with the Vesc BLDC controler (http://vedder.se/2015/01/vesc-open-source-esc/)
+It is used in the ArduBoardControl. Refer here: https://github.com/RollingGecko/ArduBoardControler
+
+The files libraries
+
+crc
+
+datatypes
+
+buffer
+
+are directly forked from https://github.com/vedderb/bldc
+
+
+All available UART handlers the VESC can deal with can be found in the file commands.c (https://github.com/vedderb/bldc)
+in the function commands_process_packet. You can write easily own handler functions. Use converting functions in
+the library buffer.c.
+
+The rest shut be comment sufficient in the VescUart.h. Take also a look to the RX-Site of the ArduBoardControler (https://github.com/RollingGecko/ArduBoardControler)
+
+##Requirements to use this library on bldc FW
+
+The needed changes where already merged by Vedder to the FW. :)
+
+In bldc-tool please activate UART and if needed the nunchuk application.
+
+
+
+##Some details to the UART port used in the VESC
+
+It is a uint8_t byte stream.
+
+First byte:
+
+0x02 for payload length of 256 byte >> next byte is for the payload length
+
+0x03 for >256 byte payload length >> next 2 byte for the payload length
+
+The follwing 2 bytes after the payload are the checksum. (see crc.h)
+
+The byte stream it terminated with a 0x03.
+
+For more details please refer also to http://vedder.se/2015/10/communicating-with-the-vesc-using-uart/
+
+
+
diff --git a/src/VescUartControl-VESC6/VescUart.cpp b/src/VescUartControl-VESC6/VescUart.cpp
new file mode 100644
index 0000000..ffdd8ec
--- /dev/null
+++ b/src/VescUartControl-VESC6/VescUart.cpp
@@ -0,0 +1,556 @@
+/*
+Copyright 2015 - 2017 Andreas Chaitidis Andreas.Chaitidis@gmail.com
+
+This program is free software : you can redistribute it and / or modify
+it under the terms of the GNU General Public License as published by
+the Free Software Foundation, either version 3 of the License, or
+(at your option) any later version.
+
+This program is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.See the
+GNU General Public License for more details.
+
+You should have received a copy of the GNU General Public License
+along with this program.If not, see .
+*/
+
+#include "VescUart.h"
+#include "buffer.h"
+#include "crc.h"
+#include "datatypes.h"
+//#include
+
+
+static SerialType* serialPort1;
+static SerialType* serialPort2;
+static SerialType* serialPort3;
+static SerialType* serialPort4;
+static SerialType* debugSerialPort = NULL;
+
+bool UnpackPayload(uint8_t* message, int lenMes, uint8_t* payload, int lenPa);
+bool ProcessReadPacket(uint8_t* message, struct bldcMeasure& values, int len);
+
+void SetSerialPort(SerialType* _serialPort1, SerialType* _serialPort2, SerialType* _serialPort3, SerialType* _serialPort4)
+{
+ serialPort1 = _serialPort1;
+ serialPort2 = _serialPort2;
+ serialPort3 = _serialPort3;
+ serialPort4 = _serialPort4;
+}
+
+void SetSerialPort(SerialType* _serialPort)
+{
+ SetSerialPort(_serialPort, _serialPort, _serialPort, _serialPort);
+}
+
+void SetDebugSerialPort(SerialType * _debugSerialPort)
+{
+ debugSerialPort = _debugSerialPort;
+}
+
+
+//SerialType *serial; ///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+int ReceiveUartMessage(uint8_t* payloadReceived, int num) {
+
+ //Messages <= 255 start with 2. 2nd byte is length
+ //Messages >255 start with 3. 2nd and 3rd byte is length combined with 1st >>8 and then &0xFF
+
+ int counter = 0;
+ int endMessage = 256;
+ bool messageRead = false;
+ uint8_t messageReceived[256];
+ int lenPayload = 0;
+ SerialType* serial;
+
+
+ switch (num) {
+ case 0:
+ serial = serialPort1;
+ break;
+ case 1:
+ serial = serialPort2;
+ break;
+ case 2:
+ serial = serialPort3;
+ break;
+ case 3:
+ serial = serialPort4;
+ break;
+ default:
+ break;
+
+ }
+
+ int mycnt=0;
+ if(!serial->available())delay(10);
+ while (serial->available()) {
+ mycnt++;
+
+ messageReceived[counter++] = serial->read();
+
+ if (counter == 2) {//case if state of 'counter' with last read 1
+
+ switch (messageReceived[0])
+ {
+ case 2:
+ endMessage = messageReceived[1] + 5; //Payload size + 2 for sice + 3 for SRC and End.
+ lenPayload = messageReceived[1];
+ break;
+ case 3:
+ //ToDo: Add Message Handling > 255 (starting with 3)
+ break;
+ default:
+ break;
+ }
+
+ }
+ if (counter >= sizeof(messageReceived))
+ {
+ break;
+ }
+
+ if (counter == endMessage && messageReceived[endMessage - 1] == 3) {//+1: Because of counter++ state of 'counter' with last read = "endMessage"
+ messageReceived[endMessage] = 0;
+ if (debugSerialPort != NULL) {
+ debugSerialPort->println("End of message reached!");
+ }
+ messageRead = true;
+ break; //Exit if end of message is reached, even if there is still more data in buffer.
+ }
+ if(!serial->available())delay(50);
+ }
+
+ bool unpacked = false;
+ if (messageRead) {
+ unpacked = UnpackPayload(messageReceived, endMessage, payloadReceived, messageReceived[1]);
+ }
+ if (unpacked)
+ {
+ //Serial.println(String("")+"payload :"+lenPayload);
+ return lenPayload; //Message was read
+
+ }
+ else {
+ //Serial.println("not unpacked :(");
+ return 0; //No Message Read
+ }
+}
+
+bool UnpackPayload(uint8_t* message, int lenMes, uint8_t* payload, int lenPay) {
+ uint16_t crcMessage = 0;
+ uint16_t crcPayload = 0;
+ //Rebuild src:
+ crcMessage = message[lenMes - 3] << 8;
+ crcMessage &= 0xFF00;
+ crcMessage += message[lenMes - 2];
+if(debugSerialPort!=NULL){
+ debugSerialPort->print("SRC received: "); debugSerialPort->println(crcMessage);
+} // DEBUG
+
+ //Extract payload:
+ memcpy(payload, &message[2], message[1]);
+
+ crcPayload = crc16(payload, message[1]);
+if(debugSerialPort!=NULL){
+ debugSerialPort->print("SRC calc: "); debugSerialPort->println(crcPayload);
+}
+ if (crcPayload == crcMessage)
+ {
+if(debugSerialPort!=NULL){
+ debugSerialPort->print("Received: "); SerialPrint(message, lenMes); debugSerialPort->println();
+ debugSerialPort->print("Payload : "); SerialPrint(payload, message[1] - 1); debugSerialPort->println();
+} // DEBUG
+
+ return true;
+ }
+ else
+ {
+ return false;
+ }
+}
+
+
+
+
+int PackSendPayload(uint8_t* payload, int lenPay, int num) {
+ uint16_t crcPayload = crc16(payload, lenPay);
+ int count = 0;
+ uint8_t messageSend[256];
+
+ if (lenPay <= 256)
+ {
+ messageSend[count++] = 2;
+ messageSend[count++] = lenPay;
+ }
+ else
+ {
+ messageSend[count++] = 3;
+ messageSend[count++] = (uint8_t)(lenPay >> 8);
+ messageSend[count++] = (uint8_t)(lenPay & 0xFF);
+ }
+ memcpy(&messageSend[count], payload, lenPay);
+
+ count += lenPay;
+ messageSend[count++] = (uint8_t)(crcPayload >> 8);
+ messageSend[count++] = (uint8_t)(crcPayload & 0xFF);
+ messageSend[count++] = 3;
+ messageSend[count] = NULL;
+
+if(debugSerialPort!=NULL){
+ debugSerialPort->print("UART package send: "); SerialPrint(messageSend, count);
+
+} // DEBUG
+
+
+ SerialType *serial;
+
+ switch (num) {
+ case 0:
+ serial=serialPort1;
+ break;
+ case 1:
+ serial=serialPort2;
+ break;
+ case 2:
+ serial=serialPort3;
+ break;
+ case 3:
+ serial=serialPort4;
+ break;
+ default:
+ break;
+ }
+
+ //Sending package
+ serial->write(messageSend, count);
+
+
+ //Returns number of send bytes
+ return count;
+}
+
+
+bool ProcessReadPacket(uint8_t* message, struct bldcMeasure& values, int len) {
+ COMM_PACKET_ID packetId;
+ int32_t ind = 0;
+
+ packetId = (COMM_PACKET_ID)message[0];
+ message++;//Eliminates the message id
+ len--;
+
+ switch (packetId)
+ {
+
+ case COMM_GET_VALUES:
+ values.tempFetFiltered = buffer_get_float16(message, 1e1, &ind);
+ values.tempMotorFiltered = buffer_get_float16(message, 1e1, &ind);
+ values.avgMotorCurrent = buffer_get_float32(message, 100.0, &ind);
+ values.avgInputCurrent = buffer_get_float32(message, 100.0, &ind);
+ values.avgId = buffer_get_float32(message, 1e2, &ind);
+ values.avgIq = buffer_get_float32(message, 1e2, &ind);
+ values.dutyNow = buffer_get_float16(message, 1000.0, &ind);
+ values.rpm = buffer_get_float32(message, 1.0, &ind);
+ values.inpVoltage = buffer_get_float16(message, 10.0, &ind);
+ values.ampHours = buffer_get_float32(message, 10000.0, &ind);
+ values.ampHoursCharged = buffer_get_float32(message, 10000.0, &ind);
+ values.wattHours = buffer_get_float32(message, 1e4, &ind);
+ values.watthoursCharged = buffer_get_float32(message, 1e4, &ind);
+ values.tachometer = buffer_get_int32(message, &ind);
+ values.tachometerAbs = buffer_get_int32(message, &ind);
+ values.faultCode = message[ind];
+ return true;
+ break;
+ default:
+ return false;
+ break;
+ }
+
+}
+/*
+bool ProcessReadPacketMC(uint8_t* message, struct mc_configuration& values, int len) {
+ COMM_PACKET_ID packetId;
+ int32_t ind = 0;
+
+ packetId = (COMM_PACKET_ID)message[0];
+ message++;//Eliminates the message id
+ len--;
+
+ switch (packetId)
+ {
+
+ case COMM_GET_MCCONF:
+
+
+ mc_pwm_mode pwm_mode;
+ mc_comm_mode comm_mode;
+ mc_motor_type motor_type;
+ mc_sensor_mode 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_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;
+ bool l_rpm_lim_neg_torque;
+ float l_temp_fet_start;
+ float l_temp_fet_end;
+ float l_temp_motor_start;
+ float l_temp_motor_end;
+ float l_min_duty;
+ float l_max_duty;
+ float lo_current_max;
+ float lo_current_min;
+ float lo_in_current_max;
+ float lo_in_current_min;
+ 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_motor_l;
+ float foc_motor_r;
+ float foc_motor_flux_linkage;
+ float foc_observer_gain;
+ 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;
+ mc_foc_sensor_mode foc_sensor_mode;
+ uint8_t foc_hall_table[8];
+ float foc_sl_erpm;
+ float s_pid_kp;
+ float s_pid_ki;
+ float s_pid_kd;
+ float s_pid_min_erpm;
+ float p_pid_kp;
+ float p_pid_ki;
+ float p_pid_kd;
+ 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_duty_ramp_step_rpm_lim;
+ float m_current_backoff_gain;
+ uint32_t m_encoder_counts;
+ sensor_port_mode m_sensor_port_mode;
+
+ values.tempFetFiltered = buffer_get_float16(message, 1e1, &ind);
+ values.tempMotorFiltered = buffer_get_float16(message, 1e1, &ind);
+ values.avgMotorCurrent = buffer_get_float32(message, 100.0, &ind);
+ values.avgInputCurrent = buffer_get_float32(message, 100.0, &ind);
+ values.avgId = buffer_get_float32(message, 1e2, &ind);
+ values.avgIq = buffer_get_float32(message, 1e2, &ind);
+ values.dutyNow = buffer_get_float16(message, 1000.0, &ind);
+ values.rpm = buffer_get_float32(message, 1.0, &ind);
+ values.inpVoltage = buffer_get_float16(message, 10.0, &ind);
+ values.ampHours = buffer_get_float32(message, 10000.0, &ind);
+ values.ampHoursCharged = buffer_get_float32(message, 10000.0, &ind);
+ values.wattHours = buffer_get_float32(message, 1e4, &ind);
+ values.watthoursCharged = buffer_get_float32(message, 1e4, &ind);
+ values.tachometer = buffer_get_int32(message, &ind);
+ values.tachometerAbs = buffer_get_int32(message, &ind);
+ values.faultCode = message[ind];
+ return true;
+ break;
+ default:
+ return false;
+ break;
+ }
+
+}*/
+int VescUartGetMC(uint8_t* values) {
+ uint8_t command[1] = { COMM_GET_MCCONF_DEFAULT };
+ uint8_t payload[512];
+ PackSendPayload(command, 1, 0);
+ //delay(0); //needed, otherwise data is not read
+ int lenPayload = ReceiveUartMessage(payload, 0);
+ if (lenPayload > 1) {
+ //bool read = ProcessReadPacketMC(payload, values, lenPayload); //returns true if sucessful
+ memcpy(values,payload+1,lenPayload-1);
+ return lenPayload;
+ }
+ else
+ {
+ return 0;
+ }
+}
+
+
+
+
+
+
+
+bool VescUartGetValue(bldcMeasure& values, int num) {
+ uint8_t command[1] = { COMM_GET_VALUES };
+ uint8_t payload[256];
+ PackSendPayload(command, 1, num);
+ delay(10); //needed, otherwise data is not read
+ int lenPayload = ReceiveUartMessage(payload, num);
+ if (lenPayload > 1) {
+ bool read = ProcessReadPacket(payload, values, lenPayload); //returns true if sucessful
+ return read;
+ }
+ else
+ {
+ return false;
+ }
+}
+
+
+bool VescUartGetValue(bldcMeasure& values) {
+ return VescUartGetValue(values, 0);
+}
+
+void VescUartSetCurrent(float current, int num) {
+ int32_t index = 0;
+ uint8_t payload[5];
+
+ payload[index++] = COMM_SET_CURRENT ;
+ buffer_append_int32(payload, (int32_t)(current * 1000), &index);
+ PackSendPayload(payload, 5, num);
+}
+void VescUartSetCurrent(float current){
+ VescUartSetCurrent(current, 0);
+}
+
+void VescUartSetPosition(float position, int num) {
+ int32_t index = 0;
+ uint8_t payload[5];
+
+ payload[index++] = COMM_SET_POS ;
+ buffer_append_int32(payload, (int32_t)(position * 1000000.0), &index);
+ PackSendPayload(payload, 5, num);
+}
+void VescUartSetPosition(float position) {
+ VescUartSetPosition(position, 0);
+}
+
+void VescUartSetDuty(float duty, int num) {
+ int32_t index = 0;
+ uint8_t payload[5];
+
+ payload[index++] = COMM_SET_DUTY ;
+ buffer_append_int32(payload, (int32_t)(duty * 100000), &index);
+ PackSendPayload(payload, 5, num);
+}
+void VescUartSetDuty(float duty) {
+ VescUartSetDuty(duty, 0);
+}
+
+
+void VescUartSetRPM(float rpm, int num) {
+ int32_t index = 0;
+ uint8_t payload[5];
+
+ payload[index++] = COMM_SET_RPM ;
+ buffer_append_int32(payload, (int32_t)(rpm), &index);
+ PackSendPayload(payload, 5, num);
+}
+void VescUartSetRPM(float rpm) {
+ VescUartSetRPM(rpm, 0);
+}
+
+void VescUartSetCurrentBrake(float brakeCurrent, int num) {
+ int32_t index = 0;
+ uint8_t payload[5];
+
+ payload[index++] = COMM_SET_CURRENT_BRAKE;
+ buffer_append_int32(payload, (int32_t)(brakeCurrent * 1000), &index);
+ PackSendPayload(payload, 5, num);
+}
+void VescUartSetCurrentBrake(float brakeCurrent) {
+ VescUartSetCurrentBrake(brakeCurrent, 0);
+}
+
+
+void VescUartSetNunchukValues(remotePackage& data, int num) {
+ int32_t ind = 0;
+ uint8_t payload[11];
+ payload[ind++] = COMM_SET_CHUCK_DATA;
+ payload[ind++] = data.valXJoy;
+ payload[ind++] = data.valYJoy;
+ buffer_append_bool(payload, data.valLowerButton, &ind);
+ buffer_append_bool(payload, data.valUpperButton, &ind);
+ //Acceleration Data. Not used, Int16 (2 byte)
+ payload[ind++] = 0;
+ payload[ind++] = 0;
+ payload[ind++] = 0;
+ payload[ind++] = 0;
+ payload[ind++] = 0;
+ payload[ind++] = 0;
+
+if(debugSerialPort!=NULL){
+ debugSerialPort->println("Data reached at VescUartSetNunchuckValues:");
+ debugSerialPort->print("valXJoy = "); debugSerialPort->print(data.valXJoy); debugSerialPort->print(" valYJoy = "); debugSerialPort->println(data.valYJoy);
+ debugSerialPort->print("LowerButton = "); debugSerialPort->print(data.valLowerButton); debugSerialPort->print(" UpperButton = "); debugSerialPort->println(data.valUpperButton);
+}
+
+ PackSendPayload(payload, 11, num);
+}
+void VescUartSetNunchukValues(remotePackage& data) {
+ VescUartSetNunchukValues(data, 0);
+}
+
+
+void SerialPrint(uint8_t* data, int len) {
+
+ // debugSerialPort->print("Data to display: "); debugSerialPort->println(sizeof(data));
+
+ for (int i = 0; i <= len; i++)
+ {
+ debugSerialPort->print(data[i]);
+ debugSerialPort->print(" ");
+ }
+ debugSerialPort->println("");
+}
+
+
+void SerialPrint(const struct bldcMeasure& values) {
+ debugSerialPort->print("tempFetFiltered: "); debugSerialPort->println(values.tempFetFiltered);
+ debugSerialPort->print("tempMotorFiltered:"); debugSerialPort->println(values.tempMotorFiltered);
+ debugSerialPort->print("avgMotorCurrent: "); debugSerialPort->println(values.avgMotorCurrent);
+ debugSerialPort->print("avgInputCurrent: "); debugSerialPort->println(values.avgInputCurrent);
+ debugSerialPort->print("avgId: "); debugSerialPort->println(values.avgId);
+ debugSerialPort->print("avgIq: "); debugSerialPort->println(values.avgIq);
+ debugSerialPort->print("dutyNow: "); debugSerialPort->println(values.dutyNow);
+ debugSerialPort->print("rpm: "); debugSerialPort->println(values.rpm);
+ debugSerialPort->print("inpVoltage: "); debugSerialPort->println(values.inpVoltage);
+ debugSerialPort->print("ampHours: "); debugSerialPort->println(values.ampHours);
+ debugSerialPort->print("ampHoursCharged: "); debugSerialPort->println(values.ampHoursCharged);
+ debugSerialPort->print("wattHours: "); debugSerialPort->println(values.wattHours);
+ debugSerialPort->print("wattHoursCharged: "); debugSerialPort->println(values.watthoursCharged);
+ debugSerialPort->print("tachometer: "); debugSerialPort->println(values.tachometer);
+ debugSerialPort->print("tachometerAbs: "); debugSerialPort->println(values.tachometerAbs);
+ debugSerialPort->print("faultCode: "); debugSerialPort->println(values.faultCode);
+
+
+}
diff --git a/src/VescUartControl-VESC6/VescUart.h b/src/VescUartControl-VESC6/VescUart.h
new file mode 100644
index 0000000..e0e7f29
--- /dev/null
+++ b/src/VescUartControl-VESC6/VescUart.h
@@ -0,0 +1,167 @@
+/*
+Copyright 2015 - 2017 Andreas Chaitidis Andreas.Chaitidis@gmail.com
+
+This program is free software : you can redistribute it and / or modify
+it under the terms of the GNU General Public License as published by
+the Free Software Foundation, either version 3 of the License, or
+(at your option) any later version.
+
+This program is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.See the
+GNU General Public License for more details.
+
+You should have received a copy of the GNU General Public License
+along with this program.If not, see .
+
+*/
+
+#ifndef _VESCUART_h
+#define _VESCUART_h
+
+
+#define SerialType HardwareSerial
+
+//#include
+#include
+//#include
+
+void SetSerialPort(SerialType* _serialPort1, SerialType* _serialPort2, SerialType* _serialPort3, SerialType* _serialPort4);
+void SetSerialPort(SerialType* _serialPort);
+void SetDebugSerialPort(SerialType* _debugSerialPort);
+
+
+
+/*TThis library was created on an Adruinio 2560 with different serial ports to have a better possibility
+to debug. The serial ports are define with #define:
+#define SERIALIO Serial1 for the UART port to VESC
+#define DEBUGSERIAL Serial for debugging over USB
+So you need here to define the right serial port for your arduino.
+If you want to use debug, uncomment DEBUGSERIAL and define a port.*/
+
+
+//#ifndef _CONFIG_h
+//
+//#ifdef __AVR_ATmega2560__
+//#define SERIALIO0 Serial
+//#define SERIALIO1 Serial1
+//#define SERIALIO2 Serial2
+//#define SERIALIO3 Serial3
+//#define DEBUGSERIAL Serial1
+//#endif
+//
+//#ifdef ARDUINO_AVR_NANO
+//#define SERIALIO0 Serial
+//#define SERIALIO1 Serial
+//#define SERIALIO2 Serial
+//#define SERIALIO3 Serial
+//#ifdef DEBUG
+////#define DEBUGSERIAL Serial
+//#endif
+////TODO: ifndef DEBUG trow build exception
+//#endif
+//#endif
+
+#if defined(ARDUINO) && ARDUINO >= 100
+#include "Arduino.h"
+#else
+#include "WProgram.h"
+#endif
+
+#include "datatypes.h"
+#include "local_datatypes.h"
+
+
+int VescUartGetMC(uint8_t* values);
+
+///SetSerialPort sets the serial to communicate with the VESC
+///Multiple ports possible
+void SetSerialPort(SerialType* _serialPort1, SerialType* _serialPort2, SerialType* _serialPort3, SerialType* _serialPort4);
+void SetSerialPort(SerialType* _serialPort);
+
+///SetDebugSerialPort sets the serial for debug information
+
+void SetDebugSerialPort(SerialType* _debugSerialPort);
+
+///PackSendPayload Packs the payload and sends it over Serial.
+///Define in a Config.h a SERIAL with the Serial in Arduino Style you want to you
+///@param: payload as the payload [unit8_t Array] with length of int lenPayload
+///@return the number of bytes send
+
+int PackSendPayload(uint8_t* payload, int lenPay, int num);
+
+///ReceiveUartMessage receives the a message over Serial
+///Define in a Config.h a SERIAL with the Serial in Arduino Style you want to you
+///@parm the payload as the payload [unit8_t Array]
+///@return the number of bytes receeived within the payload
+
+int ReceiveUartMessage(uint8_t* payloadReceived, int num);
+
+///Help Function to print struct bldcMeasure over Serial for Debug
+///#define DEBUG necessary
+///Define in a Config.h the DEBUGSERIAL you want to use
+
+void SerialPrint(const struct bldcMeasure& values);
+
+///Help Function to print uint8_t array over Serial for Debug
+///Define in a Config.h the DEBUGSERIAL you want to use
+
+void SerialPrint(uint8_t* data, int len);
+
+///Sends a command to VESC and stores the returned data
+///@param bldcMeasure struct with received data
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+//@return true if success
+bool VescUartGetValue(struct bldcMeasure& values, int num);
+bool VescUartGetValue(bldcMeasure& values);
+
+///Sends a command to VESC to control the motor current
+///@param current as float with the current for the motor
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetCurrent(float current, int num);
+void VescUartSetCurrent(float current);
+
+///Sends a command to VESC to control the motor brake
+///@param breakCurrent as float with the current for the brake
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetCurrentBrake(float brakeCurrent, int num);
+void VescUartSetCurrentBrake(float brakeCurrent);
+
+///Sends values of a joystick and 2 buttons to VESC to control the nunchuk app
+///@param struct remotePackage with all values
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetNunchukValues(remotePackage& data, int num);
+void VescUartSetNunchukValues(remotePackage& data);
+
+///Sends a command to VESC to control the motor position
+///@param position as float with the position in degrees for the motor
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetPosition(float position, int num) ;
+void VescUartSetPosition(float position) ;
+
+///Sends a command to VESC to control the motor duty cycle
+///@param duty as float with the duty cycle for the motor
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetDuty(float duty, int num) ;
+void VescUartSetDuty(float duty) ;
+
+///Sends a command to VESC to control the motor rotational speed
+///@param rpm as float with the revolutions per second for the motor
+///@param num as integer with the serial port in use (0=Serial; 1=Serial1; 2=Serial2; 3=Serial3;)
+///num must not be set, when only one Serial
+
+void VescUartSetRPM(float rpm, int num);
+void VescUartSetRPM(float rpm);
+
+#endif
diff --git a/src/VescUartControl-VESC6/buffer.cpp b/src/VescUartControl-VESC6/buffer.cpp
new file mode 100644
index 0000000..90e1743
--- /dev/null
+++ b/src/VescUartControl-VESC6/buffer.cpp
@@ -0,0 +1,127 @@
+/*
+ Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * buffer.c
+ *
+ * Created on: 13 maj 2013
+ * Author: benjamin
+ */
+
+#include "buffer.h"
+
+void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index) {
+ buffer[(*index)++] = number >> 8;
+ buffer[(*index)++] = number;
+}
+
+void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index) {
+ buffer[(*index)++] = number >> 8;
+ buffer[(*index)++] = number;
+}
+
+void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index) {
+ buffer[(*index)++] = number >> 24;
+ buffer[(*index)++] = number >> 16;
+ buffer[(*index)++] = number >> 8;
+ buffer[(*index)++] = number;
+}
+
+void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index) {
+ buffer[(*index)++] = number >> 24;
+ buffer[(*index)++] = number >> 16;
+ buffer[(*index)++] = number >> 8;
+ buffer[(*index)++] = number;
+}
+
+void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index) {
+ buffer_append_int16(buffer, (int16_t)(number * scale), index);
+}
+
+void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index) {
+ buffer_append_int32(buffer, (int32_t)(number * scale), index);
+}
+
+int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index) {
+ int16_t res = ((uint16_t) buffer[*index]) << 8 |
+ ((uint16_t) buffer[*index + 1]);
+ *index += 2;
+ return res;
+}
+
+uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index) {
+ uint16_t res = ((uint16_t) buffer[*index]) << 8 |
+ ((uint16_t) buffer[*index + 1]);
+ *index += 2;
+ return res;
+}
+
+int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index) {
+ int32_t res = ((uint32_t) buffer[*index]) << 24 |
+ ((uint32_t) buffer[*index + 1]) << 16 |
+ ((uint32_t) buffer[*index + 2]) << 8 |
+ ((uint32_t) buffer[*index + 3]);
+ *index += 4;
+ return res;
+}
+
+uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index) {
+ uint32_t res = ((uint32_t) buffer[*index]) << 24 |
+ ((uint32_t) buffer[*index + 1]) << 16 |
+ ((uint32_t) buffer[*index + 2]) << 8 |
+ ((uint32_t) buffer[*index + 3]);
+ *index += 4;
+ return res;
+}
+
+float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index) {
+ return (float)buffer_get_int16(buffer, index) / scale;
+}
+
+float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index) {
+ return (float)buffer_get_int32(buffer, index) / scale;
+}
+
+bool buffer_get_bool(const uint8_t *buffer, int32_t *index) {
+
+ if (buffer[*index] == 1)
+ {
+ index++;
+ return true;
+ }
+ else
+ {
+ index++;
+ return false;
+ }
+
+}
+
+void buffer_append_bool(uint8_t *buffer,bool value, int32_t *index) {
+
+ if (value == true)
+ {
+ buffer[*index] = 1;
+ (*index)++;
+ }
+ else
+ {
+ buffer[*index] = 0;
+ (*index)++;
+ }
+
+}
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/buffer.h b/src/VescUartControl-VESC6/buffer.h
new file mode 100644
index 0000000..d84a1f2
--- /dev/null
+++ b/src/VescUartControl-VESC6/buffer.h
@@ -0,0 +1,44 @@
+/*
+ Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * buffer.h
+ *
+ * Created on: 13 maj 2013
+ * Author: benjamin
+ */
+
+#ifndef BUFFER_H_
+#define BUFFER_H_
+
+#include
+
+void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index);
+void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index);
+void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index);
+void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index);
+void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index);
+void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index);
+int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index);
+uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index);
+int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index);
+uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index);
+float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index);
+float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index);
+bool buffer_get_bool(const uint8_t *buffer, int32_t *index);
+void buffer_append_bool(uint8_t *buffer,bool value, int32_t *index);
+#endif /* BUFFER_H_ */
diff --git a/src/VescUartControl-VESC6/crc.cpp b/src/VescUartControl-VESC6/crc.cpp
new file mode 100644
index 0000000..9768b84
--- /dev/null
+++ b/src/VescUartControl-VESC6/crc.cpp
@@ -0,0 +1,64 @@
+/*
+ Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * crc.c
+ *
+ * Created on: 26 feb 2012
+ * Author: benjamin
+ */
+#include "crc.h"
+
+// CRC Table
+const unsigned short crc16_tab[] = { 0x0000, 0x1021, 0x2042, 0x3063, 0x4084,
+ 0x50a5, 0x60c6, 0x70e7, 0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad,
+ 0xe1ce, 0xf1ef, 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7,
+ 0x62d6, 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de,
+ 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, 0xa56a,
+ 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, 0x3653, 0x2672,
+ 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, 0xb75b, 0xa77a, 0x9719,
+ 0x8738, 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, 0x48c4, 0x58e5, 0x6886, 0x78a7,
+ 0x0840, 0x1861, 0x2802, 0x3823, 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948,
+ 0x9969, 0xa90a, 0xb92b, 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50,
+ 0x3a33, 0x2a12, 0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b,
+ 0xab1a, 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41,
+ 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, 0x8d68, 0x9d49, 0x7e97,
+ 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, 0xff9f, 0xefbe,
+ 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, 0x9188, 0x81a9, 0xb1ca,
+ 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, 0x1080, 0x00a1, 0x30c2, 0x20e3,
+ 0x5004, 0x4025, 0x7046, 0x6067, 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d,
+ 0xd31c, 0xe37f, 0xf35e, 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214,
+ 0x6277, 0x7256, 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c,
+ 0xc50d, 0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
+ 0xa7db, 0xb7fa, 0x8799, 0x97b8, 0xe75f, 0xf77e, 0xc71d, 0xd73c, 0x26d3,
+ 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634, 0xd94c, 0xc96d,
+ 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, 0x5844, 0x4865, 0x7806,
+ 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e,
+ 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, 0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1,
+ 0x1ad0, 0x2ab3, 0x3a92, 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b,
+ 0x9de8, 0x8dc9, 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0,
+ 0x0cc1, 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8,
+ 0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 };
+
+unsigned short crc16(unsigned char *buf, unsigned int len) {
+ unsigned int i;
+ unsigned short cksum = 0;
+ for (i = 0; i < len; i++) {
+ cksum = crc16_tab[(((cksum >> 8) ^ *buf++) & 0xFF)] ^ (cksum << 8);
+ }
+ return cksum;
+}
diff --git a/src/VescUartControl-VESC6/crc.h b/src/VescUartControl-VESC6/crc.h
new file mode 100644
index 0000000..7d533fc
--- /dev/null
+++ b/src/VescUartControl-VESC6/crc.h
@@ -0,0 +1,33 @@
+/*
+ Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * crc.h
+ *
+ * Created on: 26 feb 2012
+ * Author: benjamin
+ */
+
+#ifndef CRC_H_
+#define CRC_H_
+
+/*
+ * Functions
+ */
+unsigned short crc16(unsigned char *buf, unsigned int len);
+
+#endif /* CRC_H_ */
diff --git a/src/VescUartControl-VESC6/datatypes.h b/src/VescUartControl-VESC6/datatypes.h
new file mode 100644
index 0000000..53fff94
--- /dev/null
+++ b/src/VescUartControl-VESC6/datatypes.h
@@ -0,0 +1,523 @@
+/*
+ Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se
+
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * datatypes.h
+ *
+ * Created on: 14 sep 2014
+ * Author: benjamin
+ */
+
+#ifndef DATATYPES_H_
+#define DATATYPES_H_
+
+#include
+#include
+//#include "ch.h"
+
+// Data types
+typedef enum {
+ MC_STATE_OFF = 0,
+ MC_STATE_DETECTING,
+ MC_STATE_RUNNING,
+ MC_STATE_FULL_BRAKE,
+} mc_state;
+
+typedef enum {
+ PWM_MODE_NONSYNCHRONOUS_HISW = 0, // This mode is not recommended
+ PWM_MODE_SYNCHRONOUS, // The recommended and most tested mode
+ PWM_MODE_BIPOLAR // Some glitches occasionally, can kill MOSFETs
+} mc_pwm_mode;
+
+typedef enum {
+ COMM_MODE_INTEGRATE = 0,
+ COMM_MODE_DELAY
+} mc_comm_mode;
+
+typedef enum {
+ SENSOR_MODE_SENSORLESS = 0,
+ SENSOR_MODE_SENSORED,
+ SENSOR_MODE_HYBRID
+} mc_sensor_mode;
+
+typedef enum {
+ FOC_SENSOR_MODE_SENSORLESS = 0,
+ FOC_SENSOR_MODE_ENCODER,
+ FOC_SENSOR_MODE_HALL
+} mc_foc_sensor_mode;
+
+typedef enum {
+ MOTOR_TYPE_BLDC = 0,
+ MOTOR_TYPE_DC,
+ MOTOR_TYPE_FOC
+} mc_motor_type;
+
+typedef enum {
+ FAULT_CODE_NONE = 0,
+ FAULT_CODE_OVER_VOLTAGE,
+ FAULT_CODE_UNDER_VOLTAGE,
+ FAULT_CODE_DRV8302,
+ FAULT_CODE_ABS_OVER_CURRENT,
+ FAULT_CODE_OVER_TEMP_FET,
+ FAULT_CODE_OVER_TEMP_MOTOR
+} mc_fault_code;
+
+typedef enum {
+ CONTROL_MODE_DUTY = 0,
+ CONTROL_MODE_SPEED,
+ CONTROL_MODE_CURRENT,
+ CONTROL_MODE_CURRENT_BRAKE,
+ CONTROL_MODE_POS,
+ CONTROL_MODE_NONE
+} mc_control_mode;
+
+typedef enum {
+ DISP_POS_MODE_NONE = 0,
+ DISP_POS_MODE_INDUCTANCE,
+ DISP_POS_MODE_OBSERVER,
+ DISP_POS_MODE_ENCODER,
+ DISP_POS_MODE_PID_POS,
+ DISP_POS_MODE_PID_POS_ERROR,
+ DISP_POS_MODE_ENCODER_OBSERVER_ERROR
+} disp_pos_mode;
+
+typedef enum {
+ SENSOR_PORT_MODE_HALL = 0,
+ SENSOR_PORT_MODE_ABI,
+ SENSOR_PORT_MODE_AS5047_SPI
+} sensor_port_mode;
+
+typedef struct {
+ float cycle_int_limit;
+ float cycle_int_limit_running;
+ float cycle_int_limit_max;
+ float comm_time_sum;
+ float comm_time_sum_min_rpm;
+ int32_t comms;
+ uint32_t time_at_comm;
+} mc_rpm_dep_struct;
+
+typedef struct {
+ // Switching and drive
+ mc_pwm_mode pwm_mode;
+ mc_comm_mode comm_mode;
+ mc_motor_type motor_type;
+ mc_sensor_mode sensor_mode;
+ // Limits
+ 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_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;
+ bool l_rpm_lim_neg_torque;
+ float l_temp_fet_start;
+ float l_temp_fet_end;
+ float l_temp_motor_start;
+ float l_temp_motor_end;
+ float l_min_duty;
+ float l_max_duty;
+ // Overridden limits (Computed during runtime)
+ float lo_current_max;
+ float lo_current_min;
+ float lo_in_current_max;
+ float lo_in_current_min;
+ // Sensorless
+ 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;
+ // Hall sensor
+ int8_t hall_table[8];
+ float hall_sl_erpm;
+ // FOC
+ 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_motor_l;
+ float foc_motor_r;
+ float foc_motor_flux_linkage;
+ float foc_observer_gain;
+ 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;
+ mc_foc_sensor_mode foc_sensor_mode;
+ uint8_t foc_hall_table[8];
+ float foc_sl_erpm;
+ // Speed PID
+ float s_pid_kp;
+ float s_pid_ki;
+ float s_pid_kd;
+ float s_pid_min_erpm;
+ // Pos PID
+ float p_pid_kp;
+ float p_pid_ki;
+ float p_pid_kd;
+ float p_pid_ang_div;
+ // Current controller
+ float cc_startup_boost_duty;
+ float cc_min_current;
+ float cc_gain;
+ float cc_ramp_step_max;
+ // Misc
+ int32_t m_fault_stop_time_ms;
+ float m_duty_ramp_step;
+ float m_duty_ramp_step_rpm_lim;
+ float m_current_backoff_gain;
+ uint32_t m_encoder_counts;
+ sensor_port_mode m_sensor_port_mode;
+} mc_configuration;
+
+// Applications to use
+typedef enum {
+ APP_NONE = 0,
+ APP_PPM,
+ APP_ADC,
+ APP_UART,
+ APP_PPM_UART,
+ APP_ADC_UART,
+ APP_NUNCHUK,
+ APP_NRF,
+ APP_CUSTOM
+} app_use;
+
+// PPM control types
+typedef enum {
+ PPM_CTRL_TYPE_NONE = 0,
+ PPM_CTRL_TYPE_CURRENT,
+ PPM_CTRL_TYPE_CURRENT_NOREV,
+ PPM_CTRL_TYPE_CURRENT_NOREV_BRAKE,
+ PPM_CTRL_TYPE_DUTY,
+ PPM_CTRL_TYPE_DUTY_NOREV,
+ PPM_CTRL_TYPE_PID,
+ PPM_CTRL_TYPE_PID_NOREV
+} ppm_control_type;
+
+typedef struct {
+ ppm_control_type ctrl_type;
+ float pid_max_erpm;
+ float hyst;
+ float pulse_start;
+ float pulse_end;
+ bool median_filter;
+ bool safe_start;
+ float rpm_lim_start;
+ float rpm_lim_end;
+ bool multi_esc;
+ bool tc;
+ float tc_max_diff;
+} ppm_config;
+
+// ADC control types
+typedef enum {
+ ADC_CTRL_TYPE_NONE = 0,
+ ADC_CTRL_TYPE_CURRENT,
+ ADC_CTRL_TYPE_CURRENT_REV_CENTER,
+ ADC_CTRL_TYPE_CURRENT_REV_BUTTON,
+ ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_CENTER,
+ ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_BUTTON,
+ ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_ADC,
+ ADC_CTRL_TYPE_DUTY,
+ ADC_CTRL_TYPE_DUTY_REV_CENTER,
+ ADC_CTRL_TYPE_DUTY_REV_BUTTON
+} adc_control_type;
+
+typedef struct {
+ adc_control_type ctrl_type;
+ float hyst;
+ float voltage_start;
+ float voltage_end;
+ bool use_filter;
+ bool safe_start;
+ bool cc_button_inverted;
+ bool rev_button_inverted;
+ bool voltage_inverted;
+ float rpm_lim_start;
+ float rpm_lim_end;
+ bool multi_esc;
+ bool tc;
+ float tc_max_diff;
+ uint32_t update_rate_hz;
+} adc_config;
+
+// Nunchuk control types
+typedef enum {
+ CHUK_CTRL_TYPE_NONE = 0,
+ CHUK_CTRL_TYPE_CURRENT,
+ CHUK_CTRL_TYPE_CURRENT_NOREV
+} chuk_control_type;
+
+typedef struct {
+ chuk_control_type ctrl_type;
+ float hyst;
+ float rpm_lim_start;
+ float rpm_lim_end;
+ float ramp_time_pos;
+ float ramp_time_neg;
+ float stick_erpm_per_s_in_cc;
+ bool multi_esc;
+ bool tc;
+ float tc_max_diff;
+} chuk_config;
+
+// NRF Datatypes
+typedef enum {
+ NRF_SPEED_250K = 0,
+ NRF_SPEED_1M,
+ NRF_SPEED_2M
+} NRF_SPEED;
+
+typedef enum {
+ NRF_POWER_M18DBM = 0,
+ NRF_POWER_M12DBM,
+ NRF_POWER_M6DBM,
+ NRF_POWER_0DBM
+} NRF_POWER;
+
+typedef enum {
+ NRF_AW_3 = 0,
+ NRF_AW_4,
+ NRF_AW_5
+} NRF_AW;
+
+typedef enum {
+ NRF_CRC_DISABLED = 0,
+ NRF_CRC_1B,
+ NRF_CRC_2B
+} NRF_CRC;
+
+typedef enum {
+ NRF_RETR_DELAY_250US = 0,
+ NRF_RETR_DELAY_500US,
+ NRF_RETR_DELAY_750US,
+ NRF_RETR_DELAY_1000US,
+ NRF_RETR_DELAY_1250US,
+ NRF_RETR_DELAY_1500US,
+ NRF_RETR_DELAY_1750US,
+ NRF_RETR_DELAY_2000US,
+ NRF_RETR_DELAY_2250US,
+ NRF_RETR_DELAY_2500US,
+ NRF_RETR_DELAY_2750US,
+ NRF_RETR_DELAY_3000US,
+ NRF_RETR_DELAY_3250US,
+ NRF_RETR_DELAY_3500US,
+ NRF_RETR_DELAY_3750US,
+ NRF_RETR_DELAY_4000US
+} NRF_RETR_DELAY;
+
+typedef struct {
+ NRF_SPEED speed;
+ NRF_POWER power;
+ NRF_CRC crc_type;
+ NRF_RETR_DELAY retry_delay;
+ unsigned char retries;
+ unsigned char channel;
+ unsigned char address[3];
+ bool send_crc_ack;
+} nrf_config;
+
+typedef struct {
+ // Settings
+ uint8_t controller_id;
+ uint32_t timeout_msec;
+ float timeout_brake_current;
+ bool send_can_status;
+ uint32_t send_can_status_rate_hz;
+
+ // Application to use
+ app_use app_to_use;
+
+ // PPM application settings
+ ppm_config app_ppm_conf;
+
+ // ADC application settings
+ adc_config app_adc_conf;
+
+ // UART application settings
+ uint32_t app_uart_baudrate;
+
+ // Nunchuk application settings
+ chuk_config app_chuk_conf;
+
+ // NRF application settings
+ nrf_config app_nrf_conf;
+} app_configuration;
+
+// Communication commands
+typedef enum {
+ COMM_FW_VERSION = 0,
+ COMM_JUMP_TO_BOOTLOADER,
+ COMM_ERASE_NEW_APP,
+ COMM_WRITE_NEW_APP_DATA,
+ COMM_GET_VALUES,
+ COMM_SET_DUTY,
+ COMM_SET_CURRENT,
+ COMM_SET_CURRENT_BRAKE,
+ COMM_SET_RPM,
+ COMM_SET_POS,
+ COMM_SET_DETECT,
+ COMM_SET_SERVO_POS,
+ COMM_SET_MCCONF,
+ COMM_GET_MCCONF,
+ COMM_GET_MCCONF_DEFAULT,
+ COMM_SET_APPCONF,
+ COMM_GET_APPCONF,
+ COMM_GET_APPCONF_DEFAULT,
+ COMM_SAMPLE_PRINT,
+ COMM_TERMINAL_CMD,
+ COMM_PRINT,
+ COMM_ROTOR_POSITION,
+ COMM_EXPERIMENT_SAMPLE,
+ COMM_DETECT_MOTOR_PARAM,
+ COMM_DETECT_MOTOR_R_L,
+ COMM_DETECT_MOTOR_FLUX_LINKAGE,
+ COMM_DETECT_ENCODER,
+ COMM_DETECT_HALL_FOC,
+ COMM_REBOOT,
+ COMM_ALIVE,
+ COMM_GET_DECODED_PPM,
+ COMM_GET_DECODED_ADC,
+ COMM_GET_DECODED_CHUK,
+ COMM_FORWARD_CAN,
+ COMM_SET_CHUCK_DATA,
+ COMM_CUSTOM_APP_DATA,
+ COMM_NON
+} COMM_PACKET_ID;
+
+// CAN commands
+typedef enum {
+ CAN_PACKET_SET_DUTY = 0,
+ CAN_PACKET_SET_CURRENT,
+ CAN_PACKET_SET_CURRENT_BRAKE,
+ CAN_PACKET_SET_RPM,
+ CAN_PACKET_SET_POS,
+ CAN_PACKET_FILL_RX_BUFFER,
+ CAN_PACKET_FILL_RX_BUFFER_LONG,
+ CAN_PACKET_PROCESS_RX_BUFFER,
+ CAN_PACKET_PROCESS_SHORT_BUFFER,
+ CAN_PACKET_STATUS
+} CAN_PACKET_ID;
+
+// Logged fault data
+typedef struct {
+ mc_fault_code fault;
+ float current;
+ float current_filtered;
+ float voltage;
+ float duty;
+ float rpm;
+ int tacho;
+ int cycles_running;
+ int tim_val_samp;
+ int tim_current_samp;
+ int tim_top;
+ int comm_step;
+ float temperature;
+} fault_data;
+
+// External LED state
+typedef enum {
+ LED_EXT_OFF = 0,
+ LED_EXT_NORMAL,
+ LED_EXT_BRAKE,
+ LED_EXT_TURN_LEFT,
+ LED_EXT_TURN_RIGHT,
+ LED_EXT_BRAKE_TURN_LEFT,
+ LED_EXT_BRAKE_TURN_RIGHT,
+ LED_EXT_BATT
+} LED_EXT_STATE;
+
+typedef struct {
+ int js_x;
+ int js_y;
+ int acc_x;
+ int acc_y;
+ int acc_z;
+ bool bt_c;
+ bool bt_z;
+} chuck_data;
+
+//typedef struct {
+// int id;
+// systime_t rx_time;
+// float rpm;
+// float current;
+// float duty;
+//} can_status_msg;
+
+typedef struct {
+ uint8_t js_x;
+ uint8_t js_y;
+ bool bt_c;
+ bool bt_z;
+ bool bt_push;
+ float vbat;
+} mote_state;
+
+typedef enum {
+ MOTE_PACKET_BATT_LEVEL = 0,
+ MOTE_PACKET_BUTTONS,
+ MOTE_PACKET_ALIVE,
+ MOTE_PACKET_FILL_RX_BUFFER,
+ MOTE_PACKET_FILL_RX_BUFFER_LONG,
+ MOTE_PACKET_PROCESS_RX_BUFFER,
+ MOTE_PACKET_PROCESS_SHORT_BUFFER,
+} MOTE_PACKET;
+
+struct mc_values{
+
+ float temp_fet_filtered;
+ float temp_motor_filtered;
+ float avg_Motor_Current;
+ float avg_input_current;
+ float avg_id;
+ float avg_iq;
+ float duty_now;
+ float rpm;
+ float input_voltage;
+ float amp_hours;
+ float amp_hours_charged;
+ float watt_hours;
+ float watt_hours_charged;
+ int tachometer;
+ int tachometer_abs;
+ int fault_code;
+ //mc_fault_code fault_code;
+} ;
+
+#endif /* DATATYPES_H_ */
diff --git a/src/VescUartControl-VESC6/desktop.ini b/src/VescUartControl-VESC6/desktop.ini
new file mode 100644
index 0000000..13cc08a
--- /dev/null
+++ b/src/VescUartControl-VESC6/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Dieser Ordner wird online freigegeben.
+IconFile=C:\Program Files\Google\Drive\googledrivesync.exe
+IconIndex=16
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.sln b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.sln
new file mode 100644
index 0000000..42f24b0
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.sln
@@ -0,0 +1,22 @@
+
+Microsoft Visual Studio Solution File, Format Version 12.00
+# Visual Studio 14
+VisualStudioVersion = 14.0.25123.0
+MinimumVisualStudioVersion = 10.0.40219.1
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "VescTestGetTelemetry", "VescTestGetTelemetry.vcxproj", "{C5F80730-F44F-4478-BDAE-6634EFC2CA88}"
+EndProject
+Global
+ GlobalSection(SolutionConfigurationPlatforms) = preSolution
+ Debug|x86 = Debug|x86
+ Release|x86 = Release|x86
+ EndGlobalSection
+ GlobalSection(ProjectConfigurationPlatforms) = postSolution
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.ActiveCfg = Debug|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.Build.0 = Debug|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.ActiveCfg = Release|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.Build.0 = Release|Win32
+ EndGlobalSection
+ GlobalSection(SolutionProperties) = preSolution
+ HideSolutionNode = FALSE
+ EndGlobalSection
+EndGlobal
diff --git a/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj
new file mode 100644
index 0000000..d902ad4
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj
@@ -0,0 +1,134 @@
+
+
+
+
+ Debug
+ Win32
+
+
+ Release
+ Win32
+
+
+
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}
+
+
+ VescTestGetTelemetry
+
+
+
+ Application
+ true
+
+
+ MultiByte
+
+
+ Application
+ false
+
+
+ true
+ MultiByte
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Level3
+ Disabled
+ true
+ %(AdditionalIncludeDirectories)
+ %(ForcedIncludeFiles)
+ true
+ %(PreprocessorDefinitions)
+
+
+ true
+
+
+
+
+ Level3
+ MaxSpeed
+ true
+ true
+ true
+
+
+ true
+ true
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ VisualMicroDebugger
+
+
+
+
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj.filters b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj.filters
new file mode 100644
index 0000000..f6c0dc7
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/VescTestGetTelemetry.vcxproj.filters
@@ -0,0 +1,185 @@
+
+
+
+
+ {4FC737F1-C7A5-4376-A066-2A32D752A2FF}
+ cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx
+
+
+ {93995380-89BD-4b04-88EB-625FBE52EBFB}
+ h;hh;hpp;hxx;hm;inl;inc;xsd
+
+
+ {67DA6AB6-F800-4c08-8B7A-83BB121AAD01}
+ rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms
+
+
+ {eb09453a-0890-47db-9607-1e4884b7c090}
+
+
+ {d7e8b738-ea63-46d2-b9d8-b83073c3dde5}
+
+
+ {56e8439e-cc41-4ace-b6bf-26e08bb7fa2d}
+
+
+ {69425d39-c499-4210-8dfc-a76031c12081}
+
+
+ {cd6fd157-4af7-46f6-aa4f-fe35836ba5eb}
+
+
+ {09857de3-0376-49eb-9fc3-714c3904c6df}
+
+
+ {d0589eb9-9000-4842-8ffd-e6f68df841ad}
+
+
+
+
+
+ Header Files
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\variants\mega
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/desktop.ini b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/desktop.ini
new file mode 100644
index 0000000..13cc08a
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescTestGetTelemetry/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Dieser Ordner wird online freigegeben.
+IconFile=C:\Program Files\Google\Drive\googledrivesync.exe
+IconIndex=16
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/Config.h b/src/VescUartControl-VESC6/examples/VescUartSample/Config.h
new file mode 100644
index 0000000..d4e4764
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/Config.h
@@ -0,0 +1,25 @@
+/*
+Copyright 2015 - 2017 Andreas Chaitidis Andreas.Chaitidis@gmail.com
+This program is free software : you can redistribute it and / or modify
+it under the terms of the GNU General Public License as published by
+the Free Software Foundation, either version 3 of the License, or
+(at your option) any later version.
+This program is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.See the
+GNU General Public License for more details.
+You should have received a copy of the GNU General Public License
+along with this program.If not, see .
+*/
+
+//The Config.h is a file, that I use in other programs usualy. So I define also the serial ports there. If you don't want to
+//use it, just comment the include statement in the VescUart.h out.
+
+#ifndef _CONFIG_h
+#define _CONFIG_h
+
+#define SERIALIO Serial1
+#define DEBUGSERIAL Serial
+
+
+#endif
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.ino b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.ino
new file mode 100644
index 0000000..1d7a826
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.ino
@@ -0,0 +1,60 @@
+/*
+ Name: VescUartSample.ino
+ Created: 9/26/2015 10:12:38 PM
+ Author: AC
+*/
+
+// the setup function runs once when you press reset or power the board
+// To use VescUartControl stand alone you need to define a config.h file, that should contain the Serial or you have to comment the line
+// #include Config.h out in VescUart.h
+
+//Include libraries copied from VESC
+
+#define DEBUG
+#include "Config.h"
+#include
+#include
+
+
+unsigned long count;
+
+void setup() {
+
+ //Setup UART port
+ SetSerialPort(&SERIALIO);
+ SERIALIO.begin(115200);
+#ifdef DEBUG
+ //SEtup debug port
+ SetDebugSerialPort(&DEBUGSERIAL);
+ DEBUGSERIAL.begin(115200);
+ #endif
+
+}
+
+struct bldcMeasure measuredVal;
+
+// the loop function runs over and over again until power down or reset
+void loop() {
+ //int len=0;
+ //len = ReceiveUartMessage(message);
+ //if (len > 0)
+ //{
+ // len = PackSendPayload(message, len);
+ // len = 0;
+ //}
+
+ if (VescUartGetValue(measuredVal)) {
+ DEBUGSERIAL.print("Loop: "); DEBUGSERIAL.println(count++);
+ SerialPrint(measuredVal);
+ }
+ else
+ {
+ Serial.println("Failed to get data!");
+ }
+
+}
+
+
+
+
+
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.sln b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.sln
new file mode 100644
index 0000000..f47dd58
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.sln
@@ -0,0 +1,22 @@
+
+Microsoft Visual Studio Solution File, Format Version 12.00
+# Visual Studio 15
+VisualStudioVersion = 15.0.26430.14
+MinimumVisualStudioVersion = 10.0.40219.1
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "VescUartSample", "VescUartSample.vcxproj", "{C5F80730-F44F-4478-BDAE-6634EFC2CA88}"
+EndProject
+Global
+ GlobalSection(SolutionConfigurationPlatforms) = preSolution
+ Debug|x86 = Debug|x86
+ Release|x86 = Release|x86
+ EndGlobalSection
+ GlobalSection(ProjectConfigurationPlatforms) = postSolution
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.ActiveCfg = Debug|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.Build.0 = Debug|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.ActiveCfg = Release|Win32
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.Build.0 = Release|Win32
+ EndGlobalSection
+ GlobalSection(SolutionProperties) = preSolution
+ HideSolutionNode = FALSE
+ EndGlobalSection
+EndGlobal
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj
new file mode 100644
index 0000000..63052aa
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj
@@ -0,0 +1,141 @@
+
+
+
+
+ Debug
+ Win32
+
+
+ Release
+ Win32
+
+
+
+ {C5F80730-F44F-4478-BDAE-6634EFC2CA88}
+
+
+ VescUartSample
+
+
+
+ Application
+ true
+
+
+ MultiByte
+
+
+ Application
+ false
+
+
+ true
+ MultiByte
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Level3
+ Disabled
+ true
+ $(ProjectDir)..\..\..\VescUartControl;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\DEV\arduino-1.5.8\libraries;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\DEV\arduino-1.5.8\hardware\arduino\avr\libraries;$(ProjectDir)..\..\..\..\libraries;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\DEV\arduino-1.5.8\hardware\arduino\avr\cores\arduino;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\DEV\arduino-1.5.8\hardware\arduino\avr\variants\mega;$(ProjectDir)..\VescUartSample;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\dev\arduino-1.5.8\hardware\tools\avr\avr\include\;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\dev\arduino-1.5.8\hardware\tools\avr\avr\include\avr\;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\dev\arduino-1.5.8\hardware\tools\avr\avr\;$(ProjectDir)..\..\..\..\..\..\..\..\..\..\dev\arduino-1.5.8\hardware\tools\avr\lib\gcc\avr\4.8.1\include\;%(AdditionalIncludeDirectories)
+ $(ProjectDir)__vm\.VescUartSample.vsarduino.h;%(ForcedIncludeFiles)
+ false
+ __AVR_ATmega2560__;F_CPU=16000000L;ARDUINO=158;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;GCC_VERSION=40801;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions)
+
+
+ true
+
+
+
+
+ Level3
+ MaxSpeed
+ true
+ true
+ true
+
+
+ true
+ true
+ true
+
+
+
+
+
+
+
+ CppCode
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ CppCode
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ VisualMicroDebugger
+
+
+
+
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj.filters b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj.filters
new file mode 100644
index 0000000..9c76dfb
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/VescUartSample.vcxproj.filters
@@ -0,0 +1,180 @@
+
+
+
+
+ {4FC737F1-C7A5-4376-A066-2A32D752A2FF}
+ cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx
+
+
+ {93995380-89BD-4b04-88EB-625FBE52EBFB}
+ h;hh;hpp;hxx;hm;inl;inc;xsd
+
+
+ {67DA6AB6-F800-4c08-8B7A-83BB121AAD01}
+ rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms
+
+
+ {f18380e6-7a91-4934-9331-5d99023fa773}
+
+
+ {ec171034-81e3-4e0a-b289-bab8714d1072}
+
+
+ {068f43d6-1888-4dff-93bd-0dd2a6361625}
+
+
+ {fa337233-0ab9-497f-83e3-28ef4b0bc31f}
+
+
+ {1269ddfc-015a-4abf-98fc-6f0542b0637c}
+
+
+
+
+
+
+
+ Header Files
+
+
+ Header Files
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\core
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+ src\_micro-api-readonly\libraries\VescUartControl
+
+
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/__vm/.VescUartSample.vsarduino.h b/src/VescUartControl-VESC6/examples/VescUartSample/__vm/.VescUartSample.vsarduino.h
new file mode 100644
index 0000000..929d1bb
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/__vm/.VescUartSample.vsarduino.h
@@ -0,0 +1,72 @@
+/*
+ Editor: http://www.visualmicro.com
+ visual micro and the arduino ide ignore this code during compilation. this code is automatically maintained by visualmicro, manual changes to this file will be overwritten
+ the contents of the Visual Micro sketch sub folder can be deleted prior to publishing a project
+ all non-arduino files created by visual micro and all visual studio project or solution files can be freely deleted and are not required to compile a sketch (do not delete your own code!).
+ note: debugger breakpoints are stored in '.sln' or '.asln' files, knowledge of last uploaded breakpoints is stored in the upload.vmps.xml file. Both files are required to continue a previous debug session without needing to compile and upload again
+
+ Hardware: Arduino Mega w/ ATmega2560 (Mega 2560), Platform=avr, Package=arduino
+*/
+
+#if defined(_VMICRO_INTELLISENSE)
+
+#ifndef _VSARDUINO_H_
+#define _VSARDUINO_H_
+#define __AVR_ATmega2560__
+#define F_CPU 16000000L
+#define ARDUINO 158
+#define ARDUINO_AVR_MEGA2560
+#define ARDUINO_ARCH_AVR
+#define __cplusplus 201103L
+#define GCC_VERSION 40801
+#define __inline__
+#define __asm__(x)
+#define __extension__
+//#define __ATTR_PURE__
+//#define __ATTR_CONST__
+#define __inline__
+//#define __asm__
+#define __volatile__
+#define GCC_VERSION 40301
+#define volatile(va_arg)
+#define __AVR__
+typedef void *__builtin_va_list;
+#define __builtin_va_start
+#define __builtin_va_end
+//#define __DOXYGEN__
+#define __attribute__(x)
+#define NOINLINE __attribute__((noinline))
+#define prog_void
+#define PGM_VOID_P int
+#define NEW_H
+/*
+#ifndef __ATTR_CONST__
+#define __ATTR_CONST__ __attribute__((__const__))
+#endif
+
+#ifndef __ATTR_MALLOC__
+#define __ATTR_MALLOC__ __attribute__((__malloc__))
+#endif
+
+#ifndef __ATTR_NORETURN__
+#define __ATTR_NORETURN__ __attribute__((__noreturn__))
+#endif
+
+#ifndef __ATTR_PURE__
+#define __ATTR_PURE__ __attribute__((__pure__))
+#endif
+*/
+typedef unsigned char byte;
+extern "C" void __cxa_pure_virtual() {;}
+
+
+
+#include
+#include
+#undef F
+#define F(string_literal) ((const PROGMEM char *)(string_literal))
+#undef PSTR
+#define PSTR(string_literal) ((const PROGMEM char *)(string_literal))
+#include "VescUartSample.ino"
+#endif
+#endif
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/__vm/desktop.ini b/src/VescUartControl-VESC6/examples/VescUartSample/__vm/desktop.ini
new file mode 100644
index 0000000..13cc08a
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/__vm/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Dieser Ordner wird online freigegeben.
+IconFile=C:\Program Files\Google\Drive\googledrivesync.exe
+IconIndex=16
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/VescUartSample/desktop.ini b/src/VescUartControl-VESC6/examples/VescUartSample/desktop.ini
new file mode 100644
index 0000000..13cc08a
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/VescUartSample/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Dieser Ordner wird online freigegeben.
+IconFile=C:\Program Files\Google\Drive\googledrivesync.exe
+IconIndex=16
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/examples/desktop.ini b/src/VescUartControl-VESC6/examples/desktop.ini
new file mode 100644
index 0000000..13cc08a
--- /dev/null
+++ b/src/VescUartControl-VESC6/examples/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Dieser Ordner wird online freigegeben.
+IconFile=C:\Program Files\Google\Drive\googledrivesync.exe
+IconIndex=16
+
\ No newline at end of file
diff --git a/src/VescUartControl-VESC6/local_datatypes.h b/src/VescUartControl-VESC6/local_datatypes.h
new file mode 100644
index 0000000..a106879
--- /dev/null
+++ b/src/VescUartControl-VESC6/local_datatypes.h
@@ -0,0 +1,34 @@
+#ifndef LOCAL_DATATYPES_H_
+#define LOCAL_DATATYPES_H_
+
+// Added by AC to store measured values
+struct bldcMeasure {
+ float tempFetFiltered;
+ float tempMotorFiltered;
+ float avgMotorCurrent;
+ float avgInputCurrent;
+ float avgId;
+ float avgIq;
+ float dutyNow;
+ long rpm;
+ float inpVoltage;
+ float ampHours;
+ float ampHoursCharged;
+ float wattHours;
+ float watthoursCharged;
+ long tachometer;
+ long tachometerAbs;
+ int faultCode;
+};
+//Define remote Package
+
+struct remotePackage {
+
+ int valXJoy;
+ int valYJoy;
+ boolean valUpperButton;
+ boolean valLowerButton;
+
+};
+
+#endif
diff --git a/src/VescUartControl-VESC6/printf.h b/src/VescUartControl-VESC6/printf.h
new file mode 100644
index 0000000..1b853db
--- /dev/null
+++ b/src/VescUartControl-VESC6/printf.h
@@ -0,0 +1,31 @@
+/*
+ Copyright (C) 2011 James Coliz, Jr.
+
+ This program is free software; you can redistribute it and/or
+ modify it under the terms of the GNU General Public License
+ version 2 as published by the Free Software Foundation.
+ */
+
+/**
+ * @file printf.h
+ *
+ * Setup necessary to direct stdout to the Arduino Serial library, which
+ * enables 'printf'
+ */
+
+#ifndef __PRINTF_H__
+#define __PRINTF_H__
+
+int serial_putc( char c, FILE * )
+{
+ Serial.write( c );
+
+ return c;
+}
+
+void printf_begin(void)
+{
+ fdevopen( &serial_putc, 0 );
+}
+
+#endif // __PRINTF_H__