update Arduino lib to new ascii protocol

This commit is contained in:
Oskar Weigl
2018-06-09 18:24:34 -07:00
parent 375156db6c
commit bdbd0409ed
4 changed files with 65 additions and 126 deletions

View File

@@ -20,20 +20,20 @@ void setup() {
Serial.begin(115200);
while (!Serial) ; // wait for Arduino Serial Monitor to open
Serial.println("ODriveArduino alpha.");
Serial.println("ODriveArduino");
Serial.println("Setting parameters...");
// In this example we set the same parameters to both motors.
// You can of course set them different if you want.
for (int motor = 0; motor < 2; ++motor) {
odrive.SetParameter(motor, odrive.PARAM_FLOAT_CURRENT_CONTROL_CURRENT_LIM, 10.0f); // [A]
odrive.SetParameter(motor, odrive.PARAM_FLOAT_VEL_LIMIT, 20000.0f); // [counts/s]
odrive.SetParameter(motor, odrive.PARAM_FLOAT_POS_GAIN, 20.0f); // [(counts/s) / counts]
odrive.SetParameter(motor, odrive.PARAM_FLOAT_VEL_GAIN, 15.0f/10000.0f); // [A/(counts/s)]
odrive.SetParameter(motor, odrive.PARAM_FLOAT_VEL_INTEGRATOR_GAIN, 0.0f/10000.0f); // [A/(counts/s * s)]
// See the documentation or play around in odrivetool to see the available parameters
for (int axis = 0; axis < 2; ++axis) {
odrive_serial << "w axis" << axis << ".controller.config.vel_limit " << 22000.0f << '\n';
odrive_serial << "w axis" << axis << ".motor.config.current_lim " << 11.0f << '\n';
// This ends up writing something like "w axis0.motor.config.current_lim 10.0\n"
}
Serial.println("Ready!");
Serial.println("Send the character '0' or '1' to calibrate respective motor (you must do this before you can command movement)");
Serial.println("Send the character 's' to exectue test move");
Serial.println("Send the character 'b' to read bus voltage");
Serial.println("Send the character 'p' to read motor positions in a 10s loop");
@@ -44,8 +44,26 @@ void loop() {
if (Serial.available()) {
char c = Serial.read();
// Run calibration sequence
if (c == '0' || c == '1') {
int requested_state;
requested_state = ODriveArduino::AXIS_STATE_MOTOR_CALIBRATION;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(atoi(c), requested_state, true);
requested_state = ODriveArduino::AXIS_STATE_ENCODER_OFFSET_CALIBRATION;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(atoi(c), requested_state, true);
requested_state = ODriveArduino::AXIS_STATE_CLOSED_LOOP_CONTROL;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(atoi(c), requested_state, false); // don't wait
}
// Sinusoidal test move
if (c == 's') {
Serial.println("Executing test move");
for (float ph = 0.0f; ph < 6.28318530718f; ph += 0.01f) {
float pos_m0 = 20000.0f * cos(ph);
float pos_m1 = 20000.0f * sin(ph);
@@ -57,7 +75,8 @@ void loop() {
// Read bus voltage
if (c == 'b') {
Serial << "Vbus voltage: " << odrive.getBusVoltage() << '\n';
odrive_serial << "r vbus_voltage\n";
Serial << "Vbus voltage: " << odrive.readFloat() << '\n';
}
// print motor positions in a 10s loop
@@ -66,7 +85,8 @@ void loop() {
unsigned long start = millis();
while(millis() - start < duration) {
for (int motor = 0; motor < 2; ++motor) {
Serial << odrive.GetParameter(motor, odrive.PARAM_FLOAT_ENCODER_PLL_POS) << '\t';
odrive_serial << "r axis" << motor << ".encoder.pos_estimate\n";
Serial << odrive.readFloat() << '\t';
}
Serial << '\n';
}