Skip to main content

Digital Drive Out

Hardware

The AutomatePro features 24 controllable solid-state switches, configurable via software as either 6x PWM controlled Full-bridge drives or 12x Half-bridges, or any combination thereof (e.g., 2x Half-bridges & 5x Full-bridges or 10x Half-bridges & 1x Full-bridge). The drive voltage is configurable by setting the two ACTU_PWR pins to the desired voltage source, allowing the user to select the voltage for the downstream actuators. Digital Drives are disabled when the E-STOP input is low. This means that when the E-STOP is activated, all Digital Drive Outputs will be disabled until the E-STOP signal is restored.

Connector Pinout

Digital Drive Power

All digital drive outputs are powered via the ACTU_PWR pins (A57 & A60) on Connector A. These pins must be connected to a power supply capable of sourcing the appropriate current for the application, with a voltage range of 6-42VDC. The voltage bus is distributed across all digital drive outputs, necessitating uniform voltage tolerance for all downstream actuators. Each ACTU_PWR pin is rated at 40A, allowing for single-pin usage if the current remains below 40A. The GND power connections on pins B59 and B62 should match the current rating of the ACTU_PWR pins. The onboard fuses are non-resettable and limited to a maximum of 60A.

The diagram below shows the internal configuration of the Digital Drives.

SVG Image created as Graphical Drawings-Full_Drive_System.svg date 2025/02/06 13:51:48 Image generated by Eeschema-SVGACTU PWRGNDGNDACTU PWRGND60AFuseGND60AFuseGNDACTU PWRGNDMHALF_BRIDGE_DRIVE_14HALF_BRIDGE_DRIVE_02HALF_BRIDGE_DRIVE_04DD_H_04FULL_BRIDGE_DRIVE_02FULL_BRIDGE_DRIVE_03HALF_BRIDGE_DRIVE_03DD_H_03DD_L_xHALF BRIDGE DRIVE 11DD_L_02DD_L_xDD_H_xDD_L_01FULL BRIDGE DRIVE 01DD_H_01FULL_BRIDGE_DRIVE_06DD_H_01DD_L_xDD_L_xDD_H_xDD_H_xHALF_BRIDGE_DRIVE_01FULL BRIDGE DRIVE 06HALF BRIDGE DRIVE 01DD_H_07HALF_BRIDGE_DRIVE_06DD_L_xHALF_BRIDGE_DRIVE_07HALF BRIDGE DRIVE 12DD_L_xDD_H_02HALF_BRIDGE_DRIVE_13DD_L_xHALF_BRIDGE_DRIVE_12DD_H_xFULL BRIDGE DRIVE 03HALF_BRIDGE_DRIVE_09FULL_BRIDGE_DRIVE_05FULL BRIDGE DRIVE 04FULL BRIDGE DRIVE 05DD_H_02FULL BRIDGE DRIVE 02DD_H_xDD_H_06HALF_BRIDGE_DRIVE_05DD_L_xDD_L_xHALF_BRIDGE_DRIVE_08DD_L_xFULL_BRIDGE_DRIVE_01DD_L_xDD_L_xDD_H_12DD_L_12PIN A57 & A60DD_H_05DD_H_xHALF BRIDGE DRIVE 02DD_H_08FULL_BRIDGE_DRIVE_04DD_L_xDD_H_11OnboardAutomateProDD_L_11DD_L_xGNDGNDGNDGND
Important

The breakout board is limited to 40A on the ACTU_PWR and therefore should not exceed this.

Digital Drive Full-Bridge Specifications

The Digital Drives full-bridge can be configured as 6x H-Bridges, enabling bi-directional control of up to 6 DC motors. These are PWM controllable with a 0-100% duty cycle range.

ParameterValue
Voltage Range (Set by ACTU_PWR)6-42V
Drive Current Max5A
PWM controllableAll Outputs
FULL_BRIDGE_DRIVE_01
FULL_BRIDGE_DRIVE_02
FULL_BRIDGE_DRIVE_03
FULL_BRIDGE_DRIVE_04
FULL_BRIDGE_DRIVE_05
FULL_BRIDGE_DRIVE_06
PWM Switching Frequency15 kHz
Number of Full-bridges6

SVG Image created as Graphical Drawings-Fullbridge.svg date 2025/02/06 13:37:17 Image generated by Eeschema-SVGGNDACTU PWRGNDMACTU PWRDD_L_xOnboardAutomateProDD_L_xDD_H_xDD_H_xGNDACTU PWRGNDACTU PWR


Important
  1. Ensure ACTU_PWR is connected to an external power supply or the +12V_IO_OUT (pin A61) should be wired to the ATCU_PWR pin - this will use the onboard 12V supply

  2. Ensure that E-STOP input is high enable Digital Drives - this can be checked by the AutomatePro LEDs

Digital Drive Half-Bridge Specifications

The Half-bridge allows PWM controllability on all low-side drives. The first 6 high-side switches also offer PWM control, while the remaining 6-12 function as on/off switches only.

ParameterValue
Voltage Range (Set by ACTU_PWR)6-42V
Drive Current5A
PWM controllableHALF_BRIDGE_DRIVE_01
HALF_BRIDGE_DRIVE_02
HALF_BRIDGE_DRIVE_03
HALF_BRIDGE_DRIVE_04
HALF_BRIDGE_DRIVE_05
HALF_BRIDGE_DRIVE_06
HALF_BRIDGE_DRIVE_07 (Only lowside switch)
HALF_BRIDGE_DRIVE_08(Only lowside switch)
HALF_BRIDGE_DRIVE_09(Only lowside switch)
HALF_BRIDGE_DRIVE_10(Only lowside switch)
HALF_BRIDGE_DRIVE_11(Only lowside switch)
HALF_BRIDGE_DRIVE_12(Only lowside switch)
PWM Switching Frequency15 kHz
Number of Half-bridges12

SVG Image created as Graphical Drawings-Halfbridge.svg date 2025/02/06 13:37:17 Image generated by Eeschema-SVGACTU PWRGNDMDD_H_xOnboardAutomateProDD_L_xACTU PWRGND


Important
  1. Ensure ACTU_PWR is connected to an external power supply or the +12V_IO_OUT (pin A61) should be wired to the ATCU_PWR pin - this will use the onboard 12V supply

  2. Ensure that E-STOP input is high to enable Digital Drives - this can be checked by the AutomatePro LEDs

ROS API

Subscribers

TopicTypeDescription
/io/digital_drive_outautomatepro_interfaces
/msg/DigitalDriveOut
Publish the desired digital drive states to this topic. Digital Drives can be configured in various configurations as described in the Hardware section.
Each digital drive output is referred to as FUNCTION_XX, where FUNCTION is the configured mode, options are FULL_BRIDGE_DRIVE, HALF_BRIDGE_DRIVE, LOW_SIDE_DRIVE and HIGH_SIDE_DRIVE. XX is the output number, ranges for each mode is mentioned below.

LOW_SIDE_DRIVE and HIGH_SIDE_DRIVE requires hardware changes. Please contact support if you want to use it.

Inputs:
d_out_pin_id:
DataType: uint8
(Use ENUM constants defined in msg definiton.
DigitalDriveOut.FULL_BRIDGE_DRIVE_XX: 01-06
DigitalDriveOut.HALF_BRIDGE_DRIVE_XX: 01-12
DigitalDriveOut.LOW_SIDE_DRIVE_XX: 01-12
DigitalDriveOut.HIGH_SIDE_DRIVE_XX: 01-12)


direction:
DataType: bool
(Use ENUM constants defined in the msg definition.
DigitalDriveOut.FORWARD for forward
DigitalDriveOut.REVERSE for reverse )


duty_cycle_percent:
DataType: uint8
Min: 0 in percentage %
Max: 100 in percentage %

Response Rate: 200 ms

Example

Example code snippets toggles the duty cycle of Digital Drive Out 01 by publishing to the /io/digital_drive_out topic.

import rclpy
from rclpy.node import Node
from automatepro_interfaces.msg import DigitalDriveOut

class DigitalDriveOutPublisher(Node):

def __init__(self):
super().__init__('digital_drive_out_publisher')
self.publisher_ = self.create_publisher(DigitalDriveOut, '/io/digital_drive_out', 10)
self.timer = self.create_timer(1.0, self.timer_callback) # 1s
self.duty_cycle = 0

def timer_callback(self):
msg = DigitalDriveOut()
msg.d_drive_pin_id = DigitalDriveOut.HALF_BRIDGE_DRIVE_01
msg.direction = DigitalDriveOut.FORWARD
msg.percent_duty_cycle = self.duty_cycle
self.publisher_.publish(msg)
self.get_logger().info(
'Publishing DigitalDriveOut: d_out_pin_id=%d, direction=%d, duty_cycle_percent=%d' %
(msg.d_drive_pin_id, msg.direction, msg.percent_duty_cycle))
self.duty_cycle = 100 if self.duty_cycle == 0 else 0 # Toggle duty cycle between 0(ON) and 100(OFF)

def main(args=None):
rclpy.init(args=args)
node = DigitalDriveOutPublisher()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()

Run the node using the following command:

ros2 run automatepro_python_tutorials digital_drive_out_node