SW ESC Motors - Weber-State-Submarine-Project/Submarine GitHub Wiki

Software Implementation for ESC Motors

This section documents the software implementation of the ESC motor and its controller. The code is responsible for sending PWM signals to control the TD1.2E 12V Underwater Thrusters. The ESC controllers are interfaced using a Raspberry Pi and an Adafruit PWM Servo Hat for precise signal generation.


Overview of the Code

The code is a ROS 2 subscriber node (esc_subscriber) written in Python. It listens to messages on the esc_topic and controls the left and right ESC motors based on the received commands. The node uses the Adafruit ServoKit library for PWM signal generation.

Key functionalities include:

  • Arming the ESC motors: Ensures the ESC controllers are properly initialized and ready for operation.
  • Listening to control messages: Subscribes to the esc_topic to receive motor selection (Left, Right, or Arm) and power percentage values.
  • Mapping power percentages to PWM pulses: Converts power values (-100% to 100%) to corresponding PWM pulse widths for motor speed and direction control.
  • Disabling the ESC motors: Stops the motors and disables the PWM signal during shutdown.

Code Walkthrough

ROS 2 Subscriber Node

The EscSubscriber class initializes the ROS 2 node and sets up the subscription to the esc_topic. It uses the orientation_msg/Esc custom message type, which contains the following fields:

  • motor_selection: Specifies which motor to control (Left, Right, or Arm).
  • power_percentage: Defines the motor power as a percentage (-100% to 100%).

Key Methods

Arming the ESC Motors

The arm_esc method follows the arming sequence outlined in the ESC datasheet:

  1. Send a maximum throttle signal (2ms pulse width).
  2. Send a neutral throttle signal (1.5ms pulse width) to complete the arming process.

This ensures the ESC is ready to accept speed and direction commands.

Disabling the ESC Motors

The disable_esc method stops the motors by sending a neutral signal (1.5ms pulse width) and then disables the PWM output to conserve power and prevent accidental movement.

Listener Callback

The listener_callback method processes incoming messages on the esc_topic:

  1. Converts the power_percentage into a corresponding angle for the PWM signal:
    • -100% corresponds to 1ms (full reverse).
    • 0% corresponds to 1.5ms (neutral stop).
    • 100% corresponds to 2ms (full forward).
  2. Sends the PWM signal to the specified motor (Left or Right) or re-arms the ESCs if the motor_selection is Arm.

Shutdown Process

During shutdown, the node calls disable_esc to stop the motors and cleanly shuts down the ROS 2 node.


Challenges

  1. PWM Signal Generation:
    The Raspberry Pi 5 struggled with software-based PWM due to its hardware limitations and lack of library support. This was resolved by using the Adafruit PWM Servo Hat, which provided reliable and precise hardware PWM signals.

  2. Arming the ESC:
    The arming sequence required strict adherence to timing and signal specifications to ensure proper initialization.

  3. Mapping Power to PWM:
    Careful mapping of power percentages to PWM pulse widths was required to achieve smooth and accurate motor control.


Code Listing

Below is the complete code implementation for the ESC motor controller:

#!/usr/bin/env python

import rclpy
from rclpy.node import Node
from orientation_msg.msg import Esc  # Import your custom message
from adafruit_servokit import ServoKit
import time

class EscSubscriber(Node):
    left_esc = 0
    right_esc = 1

    def __init__(self):
        super().__init__('esc_subscriber')

        self.kit = ServoKit(channels=16)
        self.kit.servo[self.left_esc].set_pulse_width_range(1000, 2000)  # Typical range for ESCs
        self.kit.servo[self.right_esc].set_pulse_width_range(1000, 2000)  # Typical range for ESCs

        self.subscription = self.create_subscription(
            Esc,
            'esc_topic',
            self.listener_callback,
            10)
        self.subscription
        self.arm_esc()

    def arm_esc(self):
        self.get_logger().info('[ARM - ESC] Arming both ESCs')
        self.kit.servo[self.left_esc].angle = 180
        self.kit.servo[self.right_esc].angle = 180
        time.sleep(2)
        self.kit.servo[self.left_esc].angle = 90
        self.kit.servo[self.right_esc].angle = 90
        time.sleep(2)
        self.get_logger().info('[ARM - ESC] ESCs should now both be armed!!!')

    def disable_esc(self):
        self.get_logger().info('[DISABLE - ESC] Disabling both ESCs')
        self.kit.servo[self.left_esc].angle = 90
        self.kit.servo[self.right_esc].angle = 90
        time.sleep(1)
        self.kit.servo[self.left_esc].angle = None
        self.kit.servo[self.right_esc].angle = None

    def listener_callback(self, msg):
        motor_selected = msg.motor_selection
        power_selected = msg.power_percentage

        if -100 <= power_selected <= 100:
            angle = 90 + (power_selected * 90 / 100)
        else:
            return

        if motor_selected == 'Left':
            self.kit.servo[self.left_esc].angle = angle
        elif motor_selected == 'Right':
            self.kit.servo[self.right_esc].angle = angle
        elif motor_selected == 'Arm':
            self.arm_esc()
        else:
            self.get_logger().info(f'The following is an invalid option: "{motor_selected}"')

def main(args=None):
    rclpy.init(args=args)
    esc_subscriber = EscSubscriber()
    
    try:
        rclpy.spin(esc_subscriber)
    except KeyboardInterrupt:
        pass
    
    esc_subscriber.disable_esc()
    esc_subscriber.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()