johnkok / ros_odrive

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

Error when attempting to send CMD_AXIS_SET_VELOCITY_DUAL #6

Closed jlgreene2 closed 3 years ago

jlgreene2 commented 3 years ago

I wrote a very basic Python class to accept cmd_vel messages and translate them into odrive_ctrl messages. Upon initialization, the class sends CMD_AXIS_CLOSED_LOOP commands to both axis0, and axis1, without errors. But when I start processing cmd_vel messages, I attempt to send CMD_AXIS_SET_VELOCITY_DUAL commands, and get the following errors:

[ERROR] [1615602592.918275557]: * Error: invalid write access for axis0.controller.vel_setpoint
[ERROR] [1615602592.924280103]: * Error: invalid write access for axis1.controller.vel_setpoint

I added some logging into the odrive.cpp source, to print the values in the odrive_ctrl messages before being submitted to the motor controller.

[ INFO] [1615602599.898911961]: =====
[ INFO] [1615602599.899177059]: msg->axis    [0]
[ INFO] [1615602599.899554961]: msg->target  [0]
[ INFO] [1615602599.899742424]: msg->command [4]
[ INFO] [1615602599.900849218]: msg->fval    [0.500000]
[ INFO] [1615602599.900964039]: msg->fval2   [0.500000]
[ INFO] [1615602599.901057866]: =====

Here's the source for my Python class. Is there something in the process of setting things up that I have missed?

#!/usr/bin/env python

import rospy
from geometry_msgs.msg import Twist
from ros_odrive.msg import odrive_ctrl

class WheelDriver:

    ### Constructor ###
    def __init__(self):
      self.pub = rospy.Publisher(
        "/ros_odrive/odrive_ctrl_0x20793868304E", 
        odrive_ctrl, 
        queue_size=1)
      rospy.Subscriber("cmd_vel", Twist, self.callback)

    # cmd_vel Topic Subscriber Callback
    # Processes Twist messages, sending velocity commands 
    # to the ODrive 
    def callback(self, data):
        rospy.loginfo("Received Twist Message")

        msg = odrive_ctrl()
        msg.target = 0
        msg.command = 4  # CMD_AXIS_SET_VELOCITY_DUAL
        msg.fval = data.linear.x
        msg.fval2 = data.linear.x

        rospy.loginfo("Sending odrive message...")
        self.pub.publish(msg)

    # Setup method, sending CMD_AXIS_CLOSED_LOOP commands 
    # to each axis.
    def sendCACL(self):
        a0_msg = odrive_ctrl()
        a1_msg = odrive_ctrl()

        # Send CMD_AXIS_CLOSED_LOOP to axis0
        # Had to add this sleep call to get both messages to send.
        rospy.sleep(2) 
        rospy.loginfo("Sending CMD_AXIS_CLOSED_LOOP to axis0")
        a0_msg.target = 0
        a0_msg.command = 2
        a0_msg.axis = 0
        a0_msg.fval = 0.0
        a0_msg.fval2 = 0.0
        self.pub.publish(a0_msg)
        rospy.sleep(2)

        # Send CMD_AXIS_CLOSED_LOOP to axis1 
        rospy.loginfo("Sending CMD_AXIS_CLOSED_LOOP to axis1")
        a1_msg.target = 0
        a1_msg.command = 2
        a1_msg.axis = 1
        a1_msg.fval = 0.0
        a1_msg.fval2 = 0.0
        self.pub.publish(a1_msg)
        rospy.sleep(2)

if __name__ == '__main__':
    rospy.init_node("wheel_driver", anonymous=True)
    drvr = WheelDriver()
    drvr.sendCACL()
    rospy.spin()
johnkok commented 3 years ago

Nothing to worry about, "controller.vel_setpoint" has been changed to "controller.input_vel" for the latest firmware. Update pushed. Thanks!

jlgreene2 commented 3 years ago

Well, after one last change in odrive_utils.cpp, I was able to at least get the wheels spinning. So I'll take that as progress.

int calibrateAxis1(odrive_endpoint *endpoint, Json::Value odrive_json)
{
    float fval;
    uint8_t u32val;   <---- I had to change this to a uint32_t datatype
    bool bval;

I guess I'll spend the day today getting my differential drive code working properly now. Thanks so much for the help!