Analog In
Hardware
The AutomatePro comes with 14x Analog inputs for measuring a range of different analog sensors types, such as automotive or industral sensors.
Connector Pinout
- Connector
- Development Breakout Board


Analog Input Specifications
Parameter | Value |
---|---|
Voltage Input Range | 0-10V (optional 4-20mA input or integrated automotive 5V pullup on request) |
Sample Rate | 30Hz |
Measurement Resolution | 2.4414mV/increment (12bit) |
Number of Inputs | 14 |
ROS API
Publishers
Topic | Type | Description |
---|---|---|
/io/ain | automatepro_interfaces/msg/AnalogIn | Contains the states of the analog inputs. AutomatePro supports 14 analog input pins. Each input pin is referred to as ain_XX , where XX is the pin number, ranging from 01 to 14 . Input Pins: ain_01 - ain_14 DataType: uint16 Unit: mV Min: 0 in mV Max: 10000 in mV Sample Rate: 30Hz |
tip
Each message includes a timestamp in the header, indicating when the IO-Controller collected the data. It is recommended to use this timestamp for any time-sensitive data processing, as it ensures that transport delays are accounted for, providing accurate timing for downstream operations.
Example
Example code snippet prints the states of the analog inputs by subscribing to the /io/ain
topic.
- Python
- C++
import rclpy
from rclpy.node import Node
from automatepro_interfaces.msg import AnalogIn
class AnalogInSubscriber(Node):
def __init__(self):
super().__init__('analog_in_subscriber')
self.subscription = self.create_subscription(
AnalogIn,
'/io/analog_in',
self.subscriber_callback,
10)
def subscriber_callback(self, msg):
self.get_logger().info(
f'Received AnalogIn message:\n'
f'AIN_01: {msg.ain_01}\nAIN_02: {msg.ain_02}\nAIN_03: {msg.ain_03}\n'
f'AIN_04: {msg.ain_04}\nAIN_05: {msg.ain_05}\nAIN_06: {msg.ain_06}\n'
f'AIN_07: {msg.ain_07}\nAIN_08: {msg.ain_08}\nAIN_09: {msg.ain_09}\n'
f'AIN_10: {msg.ain_10}\nAIN_11: {msg.ain_11}\nAIN_12: {msg.ain_12}\n'
f'AIN_13: {msg.ain_13}\nAIN_14: {msg.ain_14}'
)
def main(args=None):
rclpy.init(args=args)
node = AnalogInSubscriber()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Run the node using the following command:
ros2 run automatepro_python_tutorials analog_in_node
#include <rclcpp/rclcpp.hpp>
#include <automatepro_interfaces/msg/analog_in.hpp>
class AnalogInSubscriber : public rclcpp::Node
{
public:
AnalogInSubscriber()
: Node("analog_in_subscriber")
{
subscription_ = this->create_subscription<automatepro_interfaces::msg::AnalogIn>(
"/io/analog_in", 10,
std::bind(&AnalogInSubscriber::listener_callback, this, std::placeholders::_1));
}
private:
void listener_callback(const automatepro_interfaces::msg::AnalogIn::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(),
"Received AnalogIn message:\n"
"AIN_01: %u\nAIN_02: %u\nAIN_03: %u\n"
"AIN_04: %u\nAIN_05: %u\nAIN_06: %u\n"
"AIN_07: %u\nAIN_08: %u\nAIN_09: %u\n"
"AIN_10: %u\nAIN_11: %u\nAIN_12: %u\n"
"AIN_13: %u\nAIN_14: %u",
msg->ain_01, msg->ain_02, msg->ain_03,
msg->ain_04, msg->ain_05, msg->ain_06,
msg->ain_07, msg->ain_08, msg->ain_09,
msg->ain_10, msg->ain_11, msg->ain_12,
msg->ain_13, msg->ain_14);
}
rclcpp::Subscription<automatepro_interfaces::msg::AnalogIn>::SharedPtr subscription_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<AnalogInSubscriber>());
rclcpp::shutdown();
return 0;
}
Run the node using the following command:
ros2 run automatepro_cpp_tutorials analog_in_node