johnkok / ros_odrive

Odrive motor controller C++ driver for ROS
MIT License
37 stars 18 forks source link

Errors reading ODrive via USB #5

Closed jlgreene2 closed 3 years ago

jlgreene2 commented 3 years ago

I'm having difficulty getting your ROS driver up and running for my ODrive device. I've upgraded the firmware to the latest version available, and have built a configuration file for your driver that corresponds to the brushless motors I am using. But I keep getting "Error in reading data from USB" errors when the driver attempts to take values from my configuration file.

My environment is a Jetson Xavier AGX running Ubuntu 18.04, with the ROS Melodic distribution.

Here's the console output from attempting to run the driver. Is there something basic that I am missing?

robot@robot:~/echobot/src/ros_odrive/cfg$ rosrun ros_odrive ros_odrive _od_sn:="0x20793868304E" _od_cfg:="/home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json"

[ INFO] [1615160207.836033751]: Starting ODrive...
[ INFO] [1615160207.853576110]: 1 odrive instances:
[ INFO] [1615160207.855488309]:   Instance 0: SN 0x20793868304E - cfg /home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json
[ INFO] [1615160207.878449509]: Device 0x20793868304E Found
/home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json[ INFO] [1615160208.223289145]: Setting config.brake_resistance config value
[ERROR] [1615160208.430103709]: * Error in reading data from USB!
[ INFO] [1615160208.431449138]: Setting axis0.motor.config.pole_pairs config value
[ERROR] [1615160208.639965577]: * Error in reading data from USB!
[ INFO] [1615160208.641430889]: Setting axis0.motor.config.resistance_calib_max_voltage config value
[ERROR] [1615160208.850340739]: * Error in reading data from USB!
[ INFO] [1615160208.852292812]: Setting axis0.motor.config.calibration_current config value
[ERROR] [1615160209.060455191]: * Error in reading data from USB!
[ INFO] [1615160209.062538348]: Setting axis0.motor.config.requested_current_range config value
[ERROR] [1615160209.270971940]: * Error in reading data from USB!
[ INFO] [1615160209.272920525]: Setting axis0.motor.config.current_control_bandwidth config value
[ERROR] [1615160209.481454030]: * Error in reading data from USB!
[ INFO] [1615160209.483429273]: Setting axis0.encoder.config.mode config value
[ERROR] [1615160209.490033365]: Error value for axis0.encoder.config.mode is not int
[ INFO] [1615160209.490870109]: Setting axis0.encoder.config.cpr config value
[ERROR] [1615160209.699083395]: * Error in reading data from USB!
[ INFO] [1615160209.700920994]: Setting axis0.motor.config.current_lim config value
[ERROR] [1615160209.909447714]: * Error in reading data from USB!
[ INFO] [1615160209.911773484]: Setting axis0.encoder.config.bandwidth config value
[ERROR] [1615160210.119944817]: * Error in reading data from USB!
[ INFO] [1615160210.122149359]: Setting axis0.controller.config.pos_gain config value
[ERROR] [1615160210.330863593]: * Error in reading data from USB!
[ INFO] [1615160210.333186609]: Setting axis0.controller.config.vel_gain config value
[ERROR] [1615160210.541198478]: * Error in reading data from USB!
[ INFO] [1615160210.543412397]: Setting axis0.controller.config.vel_integrator_gain config value
[ERROR] [1615160210.752319896]: * Error in reading data from USB!
[ INFO] [1615160210.754663202]: Setting axis0.controller.config.vel_limit config value
[ERROR] [1615160210.963045535]: * Error in reading data from USB!
[ INFO] [1615160210.965538838]: Setting axis0.controller.config.control_mode config value
[ERROR] [1615160210.972245337]: Error value for axis0.controller.config.control_mode is not int
[ INFO] [1615160210.973168072]: Setting axis0.encoder.config.calib_range config value
[ERROR] [1615160211.179116676]: * Error in reading data from USB!
[ INFO] [1615160211.181885682]: Setting axis1.motor.config.pole_pairs config value
[ERROR] [1615160211.390151406]: * Error in reading data from USB!
[ INFO] [1615160211.392601633]: Setting axis1.motor.config.resistance_calib_max_voltage config value
[ERROR] [1615160211.602441508]: * Error in reading data from USB!
[ INFO] [1615160211.605069607]: Setting axis1.motor.config.calibration_current config value
[ERROR] [1615160211.813062475]: * Error in reading data from USB!
[ INFO] [1615160211.815455001]: Setting axis1.motor.config.requested_current_range config value
[ERROR] [1615160212.023849148]: * Error in reading data from USB!
[ INFO] [1615160212.026118334]: Setting axis1.motor.config.current_control_bandwidth config value
[ERROR] [1615160212.234682237]: * Error in reading data from USB!
[ INFO] [1615160212.237353282]: Setting axis1.encoder.config.mode config value
[ERROR] [1615160212.243928950]: Error value for axis1.encoder.config.mode is not int
[ INFO] [1615160212.244790176]: Setting axis1.encoder.config.cpr config value
[ERROR] [1615160212.450756703]: * Error in reading data from USB!
[ INFO] [1615160212.453396482]: Setting axis1.motor.config.current_lim config value
[ERROR] [1615160212.661290439]: * Error in reading data from USB!
[ INFO] [1615160212.665451372]: Setting axis1.encoder.config.bandwidth config value
[ERROR] [1615160212.873871902]: * Error in reading data from USB!
[ INFO] [1615160212.876137632]: Setting axis1.controller.config.pos_gain config value
[ERROR] [1615160213.083520355]: * Error in reading data from USB!
[ INFO] [1615160213.085792486]: Setting axis1.controller.config.vel_gain config value
[ERROR] [1615160213.297220322]: * Error in reading data from USB!
[ INFO] [1615160213.299695349]: Setting axis1.controller.config.vel_integrator_gain config value
[ERROR] [1615160213.508536404]: * Error in reading data from USB!
[ INFO] [1615160213.510968420]: Setting axis1.controller.config.vel_limit config value
[ERROR] [1615160213.719437123]: * Error in reading data from USB!
[ INFO] [1615160213.722248020]: Setting axis1.controller.config.control_mode config value
[ERROR] [1615160213.728114537]: Error value for axis1.controller.config.control_mode is not int
[ INFO] [1615160213.729065178]: Setting axis1.encoder.config.calib_range config value
[ERROR] [1615160213.935267160]: * Error in reading data from USB!
[ERROR] [1615160213.945266063]: Error value for axis0.requested_state is not int
johnkok commented 3 years ago

It seems that the CRC for the latest firmware v0.5.1 has been changed. I have committed an update that should fix the problem. Also, please check that the hwid for your board is the same with the configured, it seems that has been changed for some newer boards:

$ lsusb
Bus 001 Device 006: ID 1209:0d32 InterBiometrics

"include/ros_odrive/odrive_endpoint.hpp":

#define ODRIVE_USB_VENDORID     0x1209
#define ODRIVE_USB_PRODUCTID    0x0D32
jlgreene2 commented 3 years ago

Well, this change got me a lot further than I where I was yesterday. With your changes, I started getting errors for all of the configuration properties that were defined as uint values. When I modified the config file to change these values over to int32 values, the error messages I was originally seeing went away. But now, I'm seeing the following error:

[ERROR] [1615247617.174880968]: Error value for axis0.requested_state is not int

I am guessing the error is at lines 48-60 of odrive.cpp, where the requested state is being retrieved using a variable named u8val.

    case (CMD_AXIS_IDLE):
            // Set channel to Idle
            u8val = AXIS_STATE_IDLE;
            writeOdriveData(endpoint, odrive_json,
                    cmd.append(".requested_state"), u8val);
             break;

    case (CMD_AXIS_CLOSED_LOOP):
            // Enable Closed Loop Control
            u8val = AXIS_STATE_CLOSED_LOOP_CONTROL;
            writeOdriveData(endpoint, odrive_json,
                    cmd.append(".requested_state"), u8val);

I'm guessing it impacts the odrive_utils.cpp code as well.

johnkok commented 3 years ago

Indeed, I had to update the requested_state control for the new types. Should be ok now.

jlgreene2 commented 3 years ago

Still seeing the error for axis0.requested_state, after cloning the repo and performing a clean catkin_make.

rosrun ros_odrive ros_odrive _od_sn:="0x20793868304E" _od_cfg:="/home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json"
[ INFO] [1615317090.337093147]: Starting ODrive...
[ INFO] [1615317090.363413894]: 1 odrive instances:
[ INFO] [1615317090.366196957]:   Instance 0: SN 0x20793868304E - cfg /home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json
[ INFO] [1615317090.396640634]: Device 0x20793868304E Found
/home/robot/echobot/src/ros_odrive/cfg/odrive_15pole.json
[ INFO] [1615317090.763109382]: Setting config.brake_resistance config value
[ INFO] [1615317090.773934237]: Setting axis0.motor.config.pole_pairs config value
[ INFO] [1615317090.785114715]: Setting axis0.motor.config.resistance_calib_max_voltage config value
[ INFO] [1615317090.796663808]: Setting axis0.motor.config.calibration_current config value
[ INFO] [1615317090.806478659]: Setting axis0.motor.config.requested_current_range config value
[ INFO] [1615317090.815625561]: Setting axis0.motor.config.current_control_bandwidth config value
[ INFO] [1615317090.825355418]: Setting axis0.encoder.config.mode config value
[ INFO] [1615317090.835695047]: Setting axis0.encoder.config.cpr config value
[ INFO] [1615317090.845539467]: Setting axis0.motor.config.current_lim config value
[ INFO] [1615317090.856512997]: Setting axis0.encoder.config.bandwidth config value
[ INFO] [1615317090.867095383]: Setting axis0.controller.config.pos_gain config value
[ INFO] [1615317090.876617652]: Setting axis0.controller.config.vel_gain config value
[ INFO] [1615317090.889510740]: Setting axis0.controller.config.vel_integrator_gain config value
[ INFO] [1615317090.899959747]: Setting axis0.controller.config.vel_limit config value
[ INFO] [1615317090.909661380]: Setting axis0.controller.config.control_mode config value
[ INFO] [1615317090.920186805]: Setting axis0.encoder.config.calib_range config value
[ INFO] [1615317090.932058465]: Setting axis1.motor.config.pole_pairs config value
[ INFO] [1615317090.942597074]: Setting axis1.motor.config.resistance_calib_max_voltage config value
[ INFO] [1615317090.952014701]: Setting axis1.motor.config.calibration_current config value
[ INFO] [1615317090.962559166]: Setting axis1.motor.config.requested_current_range config value
[ INFO] [1615317090.973873631]: Setting axis1.motor.config.current_control_bandwidth config value
[ INFO] [1615317090.983387196]: Setting axis1.encoder.config.mode config value
[ INFO] [1615317090.997044459]: Setting axis1.encoder.config.cpr config value
[ INFO] [1615317091.006876142]: Setting axis1.motor.config.current_lim config value
[ INFO] [1615317091.016330089]: Setting axis1.encoder.config.bandwidth config value
[ INFO] [1615317091.028370328]: Setting axis1.controller.config.pos_gain config value
[ INFO] [1615317091.037935765]: Setting axis1.controller.config.vel_gain config value
[ INFO] [1615317091.048617928]: Setting axis1.controller.config.vel_integrator_gain config value
[ INFO] [1615317091.059199738]: Setting axis1.controller.config.vel_limit config value
[ INFO] [1615317091.068537490]: Setting axis1.controller.config.control_mode config value
[ INFO] [1615317091.077797610]: Setting axis1.encoder.config.calib_range config value
[ERROR] [1615317091.095793614]: Error value for axis0.requested_state is not int
[ERROR] [1615317101.120779536]: Error value for axis0.requested_state is not int
[ERROR] [1615317111.350925721]: * Error in reading data from USB!
[ERROR] [1615317111.351134909]: * execFunc: Error in endpoint request!
[ERROR] [1615317111.491362095]: * Error Received data out of order
[ INFO] [1615317111.499924143]: Starting idle loop
[ERROR] [1615317111.708946049]: * Error in transfering data to USB!
[ERROR] [1615317111.922327557]: * Error in transfering data to USB!
[ERROR] [1615317112.192132954]: * Error in transfering data to USB!
[ERROR] [1615317112.405992092]: * Error in transfering data to USB!
[ERROR] [1615317112.537832203]: * Error Received data out of order
Segmentation fault (core dumped)
jlgreene2 commented 3 years ago

The journey continues.

In the odrive_utils.cpp file, there are two methods (calibrateAxis0 and calibrateAxis1, the call to the second of which is commented out) that both attempt to send values to the axis[#].requested_state using uint8_t values. I changed these to int32_t datatypes, and the code gets a little bit further. I can hear the calibration process start on axis0, and see the wheel turn. But then an error is thrown when the method attempts to save the configuration (calling function execOdriveFunc), throwing the following errors.

[ERROR] [1615342205.159178024]: * Error in reading data from USB!
[ERROR] [1615342205.160634009]: * execFunc: Error in endpoint request!

When I looked at the code for odrive_endpoint.cpp (specifically in the execFunc routine), the code looks like some functionality may be missing. There are declarations for commBuffer objects tx and rx, but nothing is done with these values before the endpointRequest is submitted.

From odrive_endpoint.cpp:

int odrive_endpoint::execFunc(int endpoint_id)
{
    commBuffer tx;
    commBuffer rx;
    int rx_length;
    int status;

    status = endpointRequest(endpoint_id, rx, rx_length, tx, 1, 0);
    if (status != LIBUSB_SUCCESS) {
        ROS_ERROR("* execFunc: Error in endpoint request!");
    }
    return status;
}

I appreciate the opportunity to continue to collaborate with you on this. My C++ skills are poor at best, but I'm learning something through the process.

johnkok commented 3 years ago

Sorry, I was using the previous fw version. I am now switching to the latest. It seems problem in saving the configuration, I am working on it.

johnkok commented 3 years ago

It seems that the problem was the default time requesting the command. The default 200mSec was not enough for having the save_configuration executed. Timeout increased.

jlgreene2 commented 3 years ago

Well, it looks like that fixed it. I was able to run through the calibration step, and get to the idle loop without errors. I guess my next step is to figure out how to write a differential drive module and have it process commands from teleop_twist_keyboard and get the motors to move.

johnkok commented 3 years ago

Nice! Thanks! Most probably you will need a node for translating the twist message to odrive (subscribing to /cmd_vel and publishing to /ros_odrive/odrivectrl...). Have a look on the diff as starting point:

--- a/src/odrive.cpp
+++ b/src/odrive.cpp
@@ -1,8 +1,16 @@
 #include "ros_odrive/odrive.hpp"
+#include "geometry_msgs/Twist.h"

 using namespace std;

 odrive *od;
+float x_speed;
+
+void msgCallbackTeleop(const geometry_msgs::Twist& msg)
+{
+    ROS_INFO("Twist X: %f", msg.linear.x);
+    x_speed = msg.linear.x;
+}

 void msgCallback(const ros_odrive::odrive_ctrl::ConstPtr& msg)
 {
@@ -229,7 +237,13 @@ int main(int argc, char **argv)
         // Process configuration file
         updateTargetConfig(od->endpoint.at(i), od->json.at(i), od->target_cfg.at(i));

+        uint32_t u32val = AXIS_STATE_CLOSED_LOOP_CONTROL;
+        writeOdriveData(od->endpoint.at(i), od->json.at(i),
+                   "axis0.requested_state", u32val);
     }
+
+    ros::Subscriber sub = nh.subscribe("/cmd_vel", 10, &msgCallbackTeleop);
+
     // Example loop - reading values and updating motor velocity
     ROS_INFO("Starting idle loop");
     while (ros::ok()) {
@@ -238,6 +252,9 @@ int main(int argc, char **argv)
             // Publish status message
             publishMessage(od->endpoint.at(i), od->json.at(i), od->odrive_pub.at(i));

+            writeOdriveData(od->endpoint.at(i), od->json.at(i),
+                    "axis0.controller.input_vel", x_speed);
+
             // update watchdog
             execOdriveFunc(od->endpoint.at(i), od->json.at(i), "axis0.watchdog_feed");
             execOdriveFunc(od->endpoint.at(i), od->json.at(i), "axis1.watchdog_feed");
jlgreene2 commented 3 years ago

Thank you sir! I'll give this a shot. I really appreciate your help and time in getting this working. I hope you and your family are remaining healthy during this trying time.