Digital Out
Hardware
The AutomatePro comes with 12x digital outputs for controlling external systems from small solenoids to LEDs or small DC motors. There are two different digital outputs available, one is setup as a highside output (DO_H_0x) which PWMs the onboard 12V as an output. The second is a Lowside sink (DO_L_0x) which sinks upto 36V with the first four being PWM controllable and
Connector Pinout
- Connector
- Development Breakout Board


Digital Output Highside (DO_H_x) Specifications
There are 6x highside digital outputs with all 6 being PWM controllable switches.
Parameter | Value |
---|---|
Output Voltage (Onstate) | +12V (from on-board 12V) |
Drive Current | 500mA |
PWM Controllable | All (DO_H_01 - DO_H_06) |
PWM Switching Frequency | 500Hz |
Number of Outputs | 6 |
Digital Output Lowside (DO_L_x) Specifications
There are 6x lowside digital outputs the first four are PWM controllable while the final two are binary on/off switches.
Parameter | Value |
---|---|
Onstate | Sinks up to 36V |
Drive Current | 500mA |
PWM Controllable | DO_L_01 DO_L_02 DO_L_03 DO_L_04 D0_L_05 & DO_L_06 are On/Off switches |
PWM Switching Frequency | 10Hz |
Number of Inputs | 6 |
ROS API
Subscribers
Topic | Type | Description |
---|---|---|
/io/digital_out | automatepro_interfaces/msg/DigitalOut | Publish the desired digital out states to this topic. AutomatePro supports 12 digital out pins (6 High Side and 6 Low Side). Each input pin is referred to as DIGITAL_OUT_H_XX or DIGITAL_OUT_L_XX , where H/L refer to High Side/Low Side , XX is the pin number, ranging from 01 to 06 . d_out_pin_id : DataType: uint8 (Use ENUM constants defined in msg definiton. DigitalOut.DIGITAL_OUT_H_XX : 01-06 DigitalOut.DIGITAL_OUT_L_XX : 01-06 ) 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 Out 01 by publishing to the /io/digital_out
topic.
- Python
- C++
import rclpy
from rclpy.node import Node
from automatepro_interfaces.msg import DigitalOut
class DigitalOutPublisher(Node):
def __init__(self):
super().__init__('digital_out_publisher')
self.publisher_ = self.create_publisher(DigitalOut, '/io/digital_out', 10)
self.timer = self.create_timer(1.0, self.timer_callback) # 1s
self.duty_cycle_sequence = [0, 50, 100, 50]
self.sequence_index = 0
def timer_callback(self):
msg = DigitalOut()
msg.d_out_pin_id = DigitalOut.DIGITAL_OUT_H_01 # Digital Out High Side Pin 01
msg.duty_cycle_percent = self.duty_cycle_sequence[self.sequence_index] # Duty Cycle: 0%, 50%, 100%, 50%
# 0% - OFF, 100% - ON
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg)
self.sequence_index = (self.sequence_index + 1) % len(self.duty_cycle_sequence)
def main(args=None):
rclpy.init(args=args)
node = DigitalOutPublisher()
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_out_node
#include <vector>
#include <rclcpp/rclcpp.hpp>
#include <automatepro_interfaces/msg/digital_out.hpp>
class DigitalOutPublisher : public rclcpp::Node
{
public:
DigitalOutPublisher()
: Node("digital_out_publisher"),
duty_cycle_sequence_{0, 50, 100, 50},
sequence_index_(0)
{
publisher_ = this->create_publisher<automatepro_interfaces::msg::DigitalOut>("/io/digital_out", 10);
timer_ = this->create_wall_timer(
std::chrono::seconds(1),
std::bind(&DigitalOutPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto msg = automatepro_interfaces::msg::DigitalOut();
msg.d_out_pin_id = automatepro_interfaces::msg::DigitalOut::DIGITAL_OUT_H_01; // Digital Out High Side Pin 01
msg.duty_cycle_percent = duty_cycle_sequence_[sequence_index_]; // Duty Cycle: 0%, 50%, 100%, 50%
// 0% - OFF, 100% - ON
publisher_->publish(msg);
RCLCPP_INFO(this->get_logger(), "Publishing: d_out_pin_id=%d, duty_cycle_percent=%d", msg.d_out_pin_id, msg.duty_cycle_percent);
// Update the sequence index
sequence_index_ = (sequence_index_ + 1) % duty_cycle_sequence_.size();
}
rclcpp::Publisher<automatepro_interfaces::msg::DigitalOut>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
std::vector<int> duty_cycle_sequence_;
size_t sequence_index_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<DigitalOutPublisher>());
rclcpp::shutdown();
return 0;
}
Run the node using the following command:
ros2 run automatepro_cpp_tutorials digital_out_node