Getting Started - aifarm-dev/odrive_ros2_control GitHub Wiki

Getting Started

This guide will provide you a minimal set of instructions to operate ODrive using ros2_control.

Setup

It is recommended to install odrivetool with root privileges, so the udev rules will be automatically added, and you will not encounter USB permissions issues.

For firmware version 0.5.3:

sudo pip3 install odrive==0.5.3.post0

Odrive Preparations

Downgrade Firmware Odrive to v0.5.3 (not odrivetool python):

  • Download Odrive Firmware Release Scroll down and Select v 0.5.3
  • power off Odrive Controller Devices
  • go to donwnload file directory and run odrivetool df ODriveFirmware_v**_***V.hex
  • turn on power Odrive Controller Devices and it starts to erase and upload new firmware.
  • Once it's finished, turn off or restart Devices. that's it.

Pre-configuartion with Odrivetool

Set up your hardware following ODrive Documentation. Please make sure that your motor and encoder are properly configured and calibrated. Set the ODrive startup sequence according to your application requirements. We assume that ODrive has finished the preset startup procedure before you start the ROS driver. We do not recommend enabling the watchdog in advance, as this may hinder the startup procedure. If you want to use watchdog, just set it in URDF. ODrive axis can be set to closed-loop control state in advance or not, anyway the ROS driver can also complete state switching. We also recommend configuring and enabling the anti-cogging function, which will significantly improve the low-speed control performance.

odrv0.config.enable_brake_resistor = True 
odrv0.config.brake_resistance = 2
odrv0.save_configuration()

Standard 6.5 inch hoverboard hub motors have 30 permanent magnet poles, and thus 15 pole pairs. If you have a different motor you need to count the magnets or have a reliable datasheet for this information.

odrv0.axis0.motor.config.pole_pairs = 15
odrv0.axis0.motor.config.current_lim = 10
odrv0.axis0.motor.config.resistance_calib_max_voltage = 4
odrv0.axis0.motor.config.current_control_bandwidth = 100

Hoverboard hub motors are quite high resistance compared to the hobby aircraft motors, so we want to use a bit higher voltage for the motor calibration, and set up the current sense gain to be more sensitive. The motors are also fairly high inductance, so we need to reduce the bandwidth of the current controller from the default to keep it stable. The KV rating of the motor also should be known. It can be measured using the “drill test”, detailed here. If you can’t perform this test, a typical value is 16.

odrv0.axis0.motor.config.torque_constant = 8.27 /16.0
odrv0.axis0.motor.config.requested_current_range = 25
odrv0.axis0.motor.config.motor_type = MOTOR_TYPE_HIGH_CURRENT
 If you set the encoder to hall mode (instead of incremental). See the pinout for instructions on

how to plug in the hall feedback. The hall feedback has 6 states for every pole pair in the motor. Since we have 15 pole pairs, we set the cpr to 15*6 = 90. Since hall sensors are low resolution feedback, we also bump up the offset calibration displacement to get better calibration accuracy.

odrv0.axis0.encoder.config.mode = ENCODER_MODE_HALL
odrv0.axis0.encoder.config.cpr = 90
odrv0.axis0.encoder.config.calib_scan_distance = 150
odrv0.config.gpio12_mode = GPIO_MODE_DIGITAL
odrv0.config.gpio13_mode = GPIO_MODE_DIGITAL
odrv0.config.gpio14_mode = GPIO_MODE_DIGITAL
odrv0.axis0.encoder.config.bandwidth = 100
odrv0.axis0.controller.config.pos_gain = 1
odrv0.axis0.controller.config.vel_gain = 0.02 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr
odrv0.axis0.controller.config.vel_integrator_gain = 0.1 * odrv0.axis0.motor.config.torque_constant * odrv0.axis0.encoder.config.cpr
odrv0.axis0.controller.config.vel_limit = 10
odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.save_configuration()

Make sure the motor is free to move, then activate the motor calibration.

ODRIVE_ERROR_DC_BUS_OVER_REGEN_CURRENT
odrv0.axis0.motor.config.pre_calibrated = True

Next step is to check the alignment between the motor and the hall sensor. Because of this step you are allowed to plug the motor phases in random order and also the hall signals can be random. Just don’t change it after calibration.

Make sure the motor is free to move and run:

odrv0.axis0.requested_state = AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION
odrv0.axis0.encoder
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis0.encoder
odrv0.axis0.encoder.config.pre_calibrated = True
odrv0.save_configuration()
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis0.controller.input_vel = 2

Your motor should spin here

odrv0.axis0.controller.input_vel = 0
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis0.config.startup_closed_loop_control = True
odrv0.save_configuration()

Apply configuartions to axis 1 the same axis0

odrv0.axis1.motor.config.pole_pairs = 15
odrv0.axis1.motor.config.current_lim = 10
odrv0.axis1.motor.config.resistance_calib_max_voltage = 4
odrv0.axis1.motor.config.current_control_bandwidth = 100
odrv0.axis1.motor.config.torque_constant = 8.27 /16.0
odrv0.axis1.motor.config.requested_current_range = 25
odrv0.axis1.motor.config.motor_type = MOTOR_TYPE_HIGH_CURRENT
odrv0.axis1.encoder.config.mode = ENCODER_MODE_HALL
odrv0.axis1.encoder.config.cpr = 90
odrv0.axis1.encoder.config.calib_scan_distance = 150
odrv0.config.gpio12_mode = GPIO_MODE_DIGITAL
odrv0.config.gpio13_mode = GPIO_MODE_DIGITAL
odrv0.config.gpio14_mode = GPIO_MODE_DIGITAL
odrv0.axis1.encoder.config.bandwidth = 100
odrv0.axis1.controller.config.pos_gain = 1
odrv0.axis1.controller.config.vel_gain = 0.02 * odrv0.axis1.motor.config.torque_constant * odrv0.axis1.encoder.config.cpr
odrv0.axis1.controller.config.vel_integrator_gain = 0.1 * odrv0.axis1.motor.config.torque_constant * odrv0.axis1.encoder.config.cpr
odrv0.axis1.controller.config.vel_limit = 10
odrv0.axis1.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.save_configuration()

Make sure the motor is free to move, then activate the motor calibration.

ODRIVE_ERROR_DC_BUS_OVER_REGEN_CURRENT
odrv0.axis1.motor.config.pre_calibrated = True

Next step is to check the alignment between the motor and the hall sensor. Because of this step you are allowed to plug the motor phases in random order and also the hall signals can be random. Just don’t change it after calibration.

Make sure the motor is free to move and run:

odrv0.axis1.requested_state = AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION
odrv0.axis1.encoder
odrv0.axis1.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis1.encoder
odrv0.axis1.encoder.config.pre_calibrated = True
odrv0.save_configuration()
odrv0.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis1.controller.input_vel = 2

Your motor should spin here

odrv0.axis1.controller.input_vel = 0
odrv0.axis1.requested_state = AXIS_STATE_IDLE
odrv0.axis1.requested_state = AXIS_STATE_IDLE

odrv0.axis1.config.startup_closed_loop_control = True
odrv0.save_configuration()

Please verify configuration

dump_errors(odrv0)

Once Configuations Finished we need to reboot odrive

odrv0.reboot()



Install dependencies:

sudo apt-get install libusb-1.0-0-dev ros-foxy-ros2-control ros-foxy-ros2-controllers ros-foxy-xacro

Clone and build odrive_ros2_control, choose the branch that matches your firmware version:

git clone -b fw-v0.5.3 https://github.com/Factor-Robotics/odrive_ros2_control.git
cd ..
colcon build

Run the demo

The demo launch file will load and start velocity controller on axis0:

ros2 launch odrive_bringup odrive.launch.py

Send velocity command in another terminal, the motor should start to rotate at a speed of 1 rad/s:

ros2 topic pub -r 100 /joint0_velocity_controller/commands std_msgs/Float64MultiArray "data: [1]"

You can monitor the status of axis0, including position, speed, torque, temperature, error code:

ros2 topic echo /dynamic_joint_states

You can also visualize tf in rviz2: rviz2

(Note: Problem with watchdog)

If have problem watchdog error: go to ../odrive_description/urdf/odrive.ros2_control.xacro increase watchdog timeout. Example <param name="watchdog_timeout">10.0</param> change to 10 seconds.


Configure your own robot

This package mainly provides hardware components implementation of ODrive. So you can use it with ros2_controllers to build various types of robots. For example, you can use a single ODrive to build a differential wheeled robot, with the help of diff_drive_controller. Or use three ODrives to build a six-axis robot arm, with the help of forward_command_controller. The corresponding hardware setup need to be added to URDF, as shown in examples. If you use multiple ODrives, you must set the serial_number of the hardware to which each joint belongs. If you only use a single ODrive, the serial_number can be set to 0, then the driver will use the only ODrive found.

⚠️ **GitHub.com Fallback** ⚠️