johnkok / ros_odrive

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

[Question] Controlling two odrive boards #3

Closed jorgemiar closed 3 years ago

jorgemiar commented 4 years ago

Sorry to bug you again. I've started working on adapting your repo so I can control 4 motors at the same time whilst using ros control (so no topic subcribing/publishing). The part I'm still trying to figure out is how to send commands to two separate odrive boards.

I'm thinking of something along the lines of:

    endpoint0 = new odrive_endpoint();
    endpoint1 = new odrive_endpoint();
    odrive_endpoint *endpoint[2] = {endpoint0, endpoint1}; //Not sure if this will work

    for (i = 0; i < 2; ++i) {
    // Enumerate Odrive target
        if (endpoint[i]->init(stoull(od_sn[i], 0, 16))) //od_sn will contain two serial numbers
        {
            ROS_ERROR("Device not found!");
            return 1;
        }

        // Read JSON from target - Do I need to json files?
        if (getJson(endpoint[i], &odrive_json)) {
            return 1;
        }
        targetJsonValid = true;
    }

But I'm not sure how to deal with the odrive_json stuff. Do you think something like this would work or am I doing it completely wrong? Will setting endpoint[i] be enough to target the right odrive? or also need to save two different odrive_json?

When I write the speed to the motor it would then look like:

uint8_t motor_to_odrive_map[4] = {0, 0, 1, 1};

int ODriveDriver::setMotorSpeed(int motor_index, float motor_speed) {
    std::string cmd;

    //Get which odrive board depending on index
    i = motor_to_odrive_map[motor_index]

    //Get which axis depending on index
    cmd = "axis"
    cmd.append(std::to_string(motor_index_map_[motor_index]))

    //Will setting endpoint[i] be enough to target the right odrive? or also need to save two diff odrive_json?
    writeOdriveData(endpoint[i], odrive_json, cmd.append(".controller.vel_setpoint"), motor_speed);

}

You can find the changes I've made here. I think the only thing left to figure out is how to deal with the endpoint/json stuff.

johnkok commented 4 years ago

Hello, no problem, it is a good idea to support more than one target on the same instance. Perhaps you can also pass the serial numbers in the module parameters and dynamically evaluate the amount of targets - supporting more than 2. You need to scan and inti all targets, as you have done with the endpoint[], or perhaps by switching odrivehandle to an array. The correct (libusb_device_handle) is enough for communicating to appropriate target, so either you can extend the odrivehandle in the init function to accommodate more target or create separate odrive_endpoint objects for each target. Both should be ok. The odrive_json normally should be the same for all targets if they are running on the same firmware version/board revision. Of course reading and saving separate odrive_json for each target will be a better solution.

jorgemiar commented 3 years ago

I'm still trying to get it to work with two odrives but can't manage to compile the files as there are some errors in my code which have more to do with my lack of experience with C++. I'm not quite sure how I can create an array with two odrive_endpoint objects.

I'm not sure this part is correct:

    endpoint0 = new odrive_endpoint();
    endpoint1 = new odrive_endpoint();
    odrive_endpoint *endpoint[2] = {endpoint0, endpoint1}; //Not sure if this will work

It's also complaining that endpoint0 and endpoint1 have not been defined, as I removed this from the top (line 7 of the file), which I believe is where you declare the endpoint object and its type:

odrive_endpoint *endpoint = NULL;

Any tips on how to proceed?

Edit: Might actually be able to use something like here. Where he switched odrive_handle to an array.

johnkok commented 3 years ago

Hello jorgemia,If you can wait few days I am planning to submit an update for supporting multiple controllers.Thanks!On Sep 8, 2020 13:54, jorgemia notifications@github.com wrote: I'm still trying to get it to work with two odrives but can't manage to compile the files as there are some errors in my code which have more to do with my lack of experience with C++. I'm not quite sure how I can create an array with two odrive_endpoint objects. I'm not sure this part is correct: endpoint0 = new odrive_endpoint(); endpoint1 = new odrive_endpoint(); odrive_endpoint *endpoint[2] = {endpoint0, endpoint1}; //Not sure if this will work

It's also complaining that endpoint0 and endpoint1 have not been defined, as I removed this from the top (line 7 of the file), which I believe is where you declare the endpoint object and its type: odrive_endpoint *endpoint = NULL; Any tips on how to proceed?

—You are receiving this because you commented.Reply to this email directly, view it on GitHub, or unsubscribe.

jorgemiar commented 3 years ago

Amazing! I'll wait for that! Thanks!

johnkok commented 3 years ago

Hello jorgemia, I have made an initial commit for supporting multiple targets. Some refactroning is still needed but it is a good starting point. you can initialize the node by passing the sn and the cfg file for each target in comma seperated format, ie: rosrun ros_odrive ros_odrive _od_sn:="0x2054306D594D","0x20553489424D" _od_cfg:="/home/123/catkin_ws/src/ros_odrive/cfg/odrive_5pole.json","/home/123/catkin_ws/src/ros_odrive/cfg/odrive_5pole.json"

jorgemiar commented 3 years ago

Thanks! I actually managed to add the stuff that I wanted from your code (watchdog etc...) to the code I was using (which was an older derivation from yours by @BenBurgessLimerick which he made to work with ROS Control). You can find my latest stuff here.

I'll definitely give your stuff a try though as it is probably better structured. Thanks for the help!