Digital In
Hardware
The AutomatePro comes with 10x digital inputs for checking the binary state of external systems. It is designed to work with a wide range of different sensors and switches.
Connector Pinout
- Connector
- Development Breakout Board


Digital Input Specifications
Parameter | Value |
---|---|
High Voltage State | 5-24V |
Low Voltage State | <2V |
Input Impedance | 2kΩ |
Sample Rate | 10Hz |
Number of Inputs | 10 |
ROS API
Publishers
Topic | Type | Description |
---|---|---|
/io/din | automatepro_interfaces/msg/DigitalIn | Contains the states of the digital in. Only published on state change or when requested. AutomatePro supports 10 digital input pins. Each input pin is referred to as din_XX , where XX is the pin number, ranging from 01 to 10 . Input Pins: din_01 -din_10 DataType: bool Response Rate: 200 ms |
Services
Service | Type | Description |
---|---|---|
/io/din/request | automatepro_interfaces/srv/ReqDigitalIn | Request to send the current state of the digital inputs. When requested, current states will be published to /io/din . |
tip
It is recommended to request the states of the digital inputs by calling the service,
immediately after subscribing to /io/din
to ensure you have the most up-to-date information.
Example
Example code snippet prints the states of the digital inputs by subscribing to the /io/din
topic.
- Python
- C++
import rclpy
from rclpy.node import Node
from automatepro_interfaces.msg import DigitalIn
from automatepro_interfaces.srv import ReqDigitalIn
class DigitalInSubscriber(Node):
def __init__(self):
super().__init__('digital_in_subscriber')
self.subscription = self.create_subscription(
DigitalIn,
'/io/din',
self.listener_callback,
10)
self.client = self.create_client(ReqDigitalIn, '/io/din/request')
self.request_state() # Request the current state of the digital inputs
def listener_callback(self, msg):
self.get_logger().info('Received DigitalIn message: %s' % [
msg.din_01, msg.din_02, msg.din_03, msg.din_04, msg.din_05,
msg.din_06, msg.din_07, msg.din_08, msg.din_09, msg.din_10])
def request_state(self):
while not self.client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
request = Trigger.Request()
self.future = self.client.call_async(request)
self.future.add_done_callback(self.service_callback)
def service_callback(self, future):
try:
response = future.result()
self.get_logger().info('Service response: %s' %
('Success' if response.success else 'Failure'))
except Exception as e:
self.get_logger().info('Service call failed %r' % (e,))
def main(args=None):
rclpy.init(args=args)
node = DigitalInSubscriber()
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_in_node
#include <rclcpp/rclcpp.hpp>
#include <automatepro_interfaces/msg/digital_in.hpp>
#include <automatepro_interfaces/srv/req_digital_in.hpp>
class DigitalInSubscriber : public rclcpp::Node
{
public:
DigitalInSubscriber()
: Node("digital_in_subscriber")
{
subscription_ = this->create_subscription<automatepro_interfaces::msg::DigitalIn>(
"/io/din", 10,
std::bind(&DigitalInSubscriber::listener_callback, this, std::placeholders::_1));
client_ = this->create_client<automatepro_interfaces::srv::ReqDigitalIn>("/io/din/request");
request_state(); // Request the current state of the digital inputs
}
private:
/*
* Callback function for the subscription
*/
void listener_callback(const automatepro_interfaces::msg::DigitalIn::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "Received DigitalIn message: %d %d %d %d %d %d %d %d %d %d",
msg->din_01, msg->din_02, msg->din_03, msg->din_04, msg->din_05,
msg->din_06, msg->din_07, msg->din_08, msg->din_09, msg->din_10);
}
/*
* Request the current state of the digital inputs
*/
void request_state()
{
while (!client_->wait_for_service(std::chrono::seconds(1))) {
RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
}
auto request = std::make_shared<automatepro_interfaces::srv::ReqDigitalIn::Request>();
using ServiceResponseFuture = rclcpp::Client<automatepro_interfaces::srv::ReqDigitalIn>::SharedFuture;
auto response_received_callback = [this](ServiceResponseFuture future) {
auto response = future.get();
if (response->success) {
RCLCPP_INFO(this->get_logger(), "Service response received: success= %d", response->success);
} else {
RCLCPP_ERROR(this->get_logger(), "Service call failed");
}
};
auto result = client_->async_send_request(request, response_received_callback);
}
rclcpp::Subscription<automatepro_interfaces::msg::DigitalIn>::SharedPtr subscription_;
rclcpp::Client<automatepro_interfaces::srv::ReqDigitalIn>::SharedPtr client_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<DigitalInSubscriber>());
rclcpp::shutdown();
return 0;
}
Run the node using the following command:
ros2 run automatepro_cpp_tutorials digital_in_node