Sending Commands from Arduino and receiving encoder data

Hello.

I am trying to send certain commands to the odrive from the Arduino like a reboot when a button is pushed but I can’t figure it out.

Here is my code…

#include <SoftwareSerial.h>
#include <ODriveArduino.h>

// Printing with stream operator
template<class T> inline Print& operator <<(Print &obj,     T arg) { obj.print(arg);    return obj; }
template<>        inline Print& operator <<(Print &obj, float arg) { obj.print(arg, 4); return obj; }

//Connect pin 8 on arduino to pin 1 in GPIO section on Odrive and pin 9 to pin 2
SoftwareSerial odrive_serial(8, 9); //RX (ODrive TX), TX (ODrive RX)

//for the throttle wire the orange wire to 5V, the black to ground, and the orange to A0

// ODrive object
ODriveArduino odrive(odrive_serial);

int n=0;
int motornum = 0;
int requested_state;
int axis=0;
int reset_button=10;

void setup() {
  // ODrive uses 115200 baud
  odrive_serial.begin(115200);//is used to send commands to odrive 

  Serial.begin(115200);

    odrive_serial << "w axis" << axis << ".controller.config.vel_limit " << 22000.0f << '\n'; //sets velocity limit
    odrive_serial << "w axis" << axis << ".motor.config.current_lim " << 60.0f << '\n'; //sets current limit
    odrive_serial << "w axis" << axis <<".motor.config.pre_calibrated = True"<<'\n'; //tells odrive its motor is calibrated 
    odrive_serial << "w axis" << axis <<".encoder.config.pre_calibrated = True"<<'\n'; //tells odrive its encoder is calibrated (both steps must be done to enter motor into closed loop control later)

    requested_state = ODriveArduino::AXIS_STATE_IDLE;
    odrive.run_state(motornum, requested_state, false); 
      
}

void loop() {

    if (digitalRead(reset_button)== LOW){
      
      Serial.println("running");
      
      float vel= analogRead(A0); //read value from hall effect sensor in throttle (values are between 177 and 880)
      
         if(vel<190){ //makes neutral positions of throttle so that motor is in idle mode
          requested_state = ODriveArduino::AXIS_STATE_IDLE;
          odrive.run_state(motornum, requested_state, false); 
         }
          
          else { //makes anything above 190 cloesed look control to use velocity control 
          requested_state = ODriveArduino::AXIS_STATE_CLOSED_LOOP_CONTROL;
          odrive.run_state(motornum, requested_state, false); 
    
          vel= map(vel,190,880,0,700); //maps values of 190 to 880 (the throttle) to 0 to 700 the counts/s for motor 
          odrive.SetVelocity(0, vel); //sets motor 0's velocity to maped value above 
          }


       if(digitalRead(reset_button)== HIGH){
         odrive_serial << "reboot()"<< '\n';
         Serial.println("rebooting");
         
    }
  }
}

I thought that this…
odrive_serial << "reboot()"<< '\n';
would do it but I guess not.

This made me question even if this (below), did what I wanted it to do…

odrive_serial << "w axis" << axis <<".motor.config.pre_calibrated = True"<<'\n'; //tells odrive its motor is calibrated
odrive_serial << "w axis" << axis <<".encoder.config.pre_calibrated = True"<<'\n'; //tells odrive its encoder is calibrated (both steps must be done to enter motor into closed loop control later)

My other question is how do I get the odrive to send the encoder velocity estimate to the arduino to use the data.

I know that you can use odrv0.axis0.encoder.vel_estimate in anaconda to pull the data but how do I do that in arduino.

I found this post https://discourse.odriverobotics.com/t/small-guide-on-how-to-use-odrivearduino-commands/1571 where it says…

And to get the encoder position and add it to a variable use two commands like this:

odrive_serial.write(“r axis0.encoder.pos_estimate\n”);
endstopPos = odrive.readFloat();

but that did not work.

Please check out the recent release of v0.4.8. It has new ascii commands, including f for feedback, and sb for reboot.

Hi @pumpkinheadnick and @madcowswe,

I’m working on a commercial project. So far it seems like Odrive is a very powerful tool. But I am having the same problem reading values from Odrive to arduino and this is holding up my code development. I have tried everything I can find that has has already been suggested on this forum. Also, the latest example arduino code which contains this script:

// print motor positions in a 10s loop
    if (c == 'p') {
      static const unsigned long duration = 10000;
      unsigned long start = millis();
      while(millis() - start < duration) {
        for (int motor = 0; motor < 2; ++motor) {
          odrive_serial << "r axis" << motor << ".encoder.pos_estimate\n";
          Serial << odrive.readFloat() << '\t';
        }
        Serial << '\n';
      }
    }

This returns 0.00 over and over on the serial monitor. When I try implement the ascii request as descibed previously, I get values of 0.00 as well.

odrive_serial.write(“r axis0.encoder.pos_estimate\n”);
endstopPos = odrive.readFloat();

When I try a similar request using the new ‘f’ ascii command instead of ‘r’, no luck also.

When I use anaconda prompt and request odrv.0.axis0.encoder.pos_estimate, it gives me a large float value which seems to be corresponding well to position, which is to be expected.

Has anyone successfully been able to read values to arduino over serial? If so and you are reading this, could you share a code snippet?

@madcowswe it would be great if you could update the example arduino code to demonstrate the use of feedback ascii command, or provide a code snipet here that will successfully read the pos_estimate value to a float variable. (I also need to read the current flowing to motors but have not attempted that yet)

Thanks.

Hi @Iain,
The provided Arduino code should work to read values in general. There is likely some issues with your UART wiring for the data going ODrive -> Arduino.

Which Arduino model are you using? Can you show us a picture of your wiring?

Yeah this should work…

odrive_serial << “r axis” << 0 <<".encoder.vel_estimate"<<’\n’; //sends command to get encoder data

Hi, perhaps I’m facing a problem that belongs to this topic. I’m using Arduino Uno and ODrive v3.6 with fw-v0.5.4. I’m testing a scenario where I want to control e.g. the position of my HooverMotor and get the velocity or position or electrical power from the ODrive encoder/controller. I’m sending the desired position by a Arduino analogread() command from a Poti with odrive.SetPosition from ODriveArduino.h to the Odrive. The communication using the SoftwareSerial.h on GPIO 1 and 2 on ODrive and pin 8 and 9 on Arduino side works fine and the motor reacts directly to the Poti position. Using a further serial to PC shows me the belonging Poti value on the serial monitor/plotter included in the arduino IDE, perfect. But: If I know include “float motVel=odrive.GetVelocity(0);” command there seams to be an interference in the communication as the motor does no longer react directly to the changing poti position but has a small and random delay. Also the monitor/plotter shows these interrupts. The velocity itself is read and can be shown on the serial plotter. My Doubt: As I didn’t find examples where the odrive.GetVelocity is applied, is it thought the way I’m using it? Do I have to use another way to read Odrive parameters to Arduino?

Hallo again,

in ODriveArduino.cpp I made two changes:

  1. In function bool ODriveArduino::run_state() I reduced delay(100) to delay(5)
  2. In function String ODriveArduino::readString() I reduced timeout = 1000 to timeout = 5

Know there is a direct reaction of the motor again and I can plot velocity, position and electrical power. Could I run in other problems because of that changes?

1 Like

Actually what you did was make the code more “real-time” in the event of any issues which is good. In theory, there should be no call to delay() at all, (it shouldn’t block), but we went for simplicity over correctness.