Device Diagnostics
Hardware
The AutomatePro is equipped with comprehensive onboard current and voltage monitoring systems. This reduces the need for external sensors and enables effective downstream monitoring, facilitating early detection of potential issues. These monitored power supply diagram is given below.

ROS API
Publishers
Topic | Type | Description |
---|---|---|
/diagnostics/io_controller_hw | automatepro_interfaces /msg/IOControllerDiagnostic | Contains the diagnostic information about the IO Controller Hardware. Fields: - vbatt_voltage_monitor (float32 ): Battery voltage in V - v12_io_smps_current_monitor (float32 ): Current level on the 12V IO SMPS in A - v12_io_smps_voltage_monitor (float32 ): Voltage level on the 12V IO SMPS in V - main_sbc_smps_current_monitor (float32 ): Current level on the 12V or 5V SBC SMPS in A - main_sbc_smps_voltage_monitor (float32 ): Voltage level on the 12V or 5V SBC SMPS in V - v5_io_smps_voltage_monitor (float32 ): Voltage level on the 5V IO SMPS in V - amp_total_power_monitor (float32 ): Total power draw in W - v12_io_power_good (bool ): Indicates if the 12V IO power is good - v5_io_power_good (bool ): Indicates if the 5V IO power is good - v3_3_io_power_good (bool ): Indicates if the 3.3V IO power is good - v12_sbc_power_good (bool ): Indicates if the 12V SBC power is good - v5_sbc_power_good (bool ): Indicates if the 5V SBC power is good - v3_3_sbc_power_good (bool ): Indicates if the 3.3V SBC power is good - v1_8_sbc_power_good (bool ): Indicates if the 1.8V SBC power is good - motor_drive_fault_1 (bool ): Indicates a fault in motor drive 1 - motor_drive_fault_2 (bool ): Indicates a fault in motor drive 2 - motor_drive_fault_3 (bool ): Indicates a fault in motor drive 3 - motor_drive_fault_4 (bool ): Indicates a fault in motor drive 4 - board_temp (int8 ): Board temperature in degrees Celsius °C |
/diagnostics/io_controller_fw | automatepro_interfaces /msg/IOFirmwareDiagnostic | Contains the diagnostic information about the IO Controller Firmware. Fields: - fault_code (uint32 ): Fault Code, check Index for more details - reserved (uint8[4] ): Reserved for internal use |
Fault Code Index
Fault Code | Description |
---|---|
0 | No Fault |
Example
Example code snippet prints the diagnostic information about the IO Controller by subscribing to the /diagnostics/io_controller_hw
topic.
- Python
- C++
import rclpy
from rclpy.node import Node
from automatepro_interfaces.msg import IOControllerDiagnostic
class IOControllerDiagnosticSubscriber(Node):
def __init__(self):
super().__init__('io_controller_diagnostic_subscriber')
self.subscription = self.create_subscription(
IOControllerDiagnostic,
'/diagnostics/io_controller_hw',
self.listener_callback,
10)
def listener_callback(self, msg):
self.get_logger().info(f'Battery Voltage: {msg.vbatt_voltage_monitor} V')
self.get_logger().info(f'12V IO SMPS Current: {msg.v12_io_smps_current_monitor} A')
self.get_logger().info(f'12V IO SMPS Voltage: {msg.v12_io_smps_voltage_monitor} V')
self.get_logger().info(f'Main SBC SMPS Current: {msg.main_sbc_smps_current_monitor} A')
self.get_logger().info(f'Main SBC SMPS Voltage: {msg.main_sbc_smps_voltage_monitor} V')
self.get_logger().info(f'5V IO SMPS Voltage: {msg.v5_io_smps_voltage_monitor} V')
self.get_logger().info(f'Total Power: {msg.amp_total_power_monitor} W')
self.get_logger().info(f'12V IO Power Good: {msg.v12_io_power_good}')
self.get_logger().info(f'5V IO Power Good: {msg.v5_io_power_good}')
self.get_logger().info(f'3.3V IO Power Good: {msg.v3_3_io_power_good}')
self.get_logger().info(f'12V SBC Power Good: {msg.v12_sbc_power_good}')
self.get_logger().info(f'5V SBC Power Good: {msg.v5_sbc_power_good}')
self.get_logger().info(f'3.3V SBC Power Good: {msg.v3_3_sbc_power_good}')
self.get_logger().info(f'1.8V SBC Power Good: {msg.v1_8_sbc_power_good}')
self.get_logger().info(f'Motor Drive Fault 1: {msg.motor_drive_fault_1}')
self.get_logger().info(f'Motor Drive Fault 2: {msg.motor_drive_fault_2}')
self.get_logger().info(f'Motor Drive Fault 3: {msg.motor_drive_fault_3}')
self.get_logger().info(f'Motor Drive Fault 4: {msg.motor_drive_fault_4}')
self.get_logger().info(f'Board Temperature: {msg.board_temp} °C')
def main(args=None):
rclpy.init(args=args)
node = IOControllerDiagnosticSubscriber()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Run the node using the following command:
ros2 run automatepro_python_tutorials io_controller_diagnostic_node
#include <rclcpp/rclcpp.hpp>
#include <automatepro_interfaces/msg/io_controller_diagnostic.hpp>
class IOControllerDiagnosticSubscriber : public rclcpp::Node
{
public:
IOControllerDiagnosticSubscriber()
: Node("io_controller_diagnostic_subscriber")
{
subscription_ = this->create_subscription<automatepro_interfaces::msg::IOControllerDiagnostic>(
"/diagnostics/io_controller_hw", 10,
std::bind(&IOControllerDiagnosticSubscriber::listener_callback, this, std::placeholders::_1));
}
private:
void listener_callback(const automatepro_interfaces::msg::IOControllerDiagnostic::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "Battery Voltage: %.3f V", msg->vbatt_voltage_monitor);
RCLCPP_INFO(this->get_logger(), "12V IO SMPS Current: %.3f A", msg->v12_io_smps_current_monitor);
RCLCPP_INFO(this->get_logger(), "12V IO SMPS Voltage: %.3f V", msg->v12_io_smps_voltage_monitor);
RCLCPP_INFO(this->get_logger(), "Main SBC SMPS Current: %.3f A", msg->main_sbc_smps_current_monitor);
RCLCPP_INFO(this->get_logger(), "Main SBC SMPS Voltage: %.3f V", msg->main_sbc_smps_voltage_monitor);
RCLCPP_INFO(this->get_logger(), "5V IO SMPS Voltage: %.3f V", msg->v5_io_smps_voltage_monitor);
RCLCPP_INFO(this->get_logger(), "Total Power: %.3f W", msg->amp_total_power_monitor);
RCLCPP_INFO(this->get_logger(), "12V IO Power Good: %d", msg->v12_io_power_good);
RCLCPP_INFO(this->get_logger(), "5V IO Power Good: %d", msg->v5_io_power_good);
RCLCPP_INFO(this->get_logger(), "3.3V IO Power Good: %d", msg->v3_3_io_power_good);
RCLCPP_INFO(this->get_logger(), "12V SBC Power Good: %d", msg->v12_sbc_power_good);
RCLCPP_INFO(this->get_logger(), "5V SBC Power Good: %d", msg->v5_sbc_power_good);
RCLCPP_INFO(this->get_logger(), "3.3V SBC Power Good: %d", msg->v3_3_sbc_power_good);
RCLCPP_INFO(this->get_logger(), "1.8V SBC Power Good: %d", msg->v1_8_sbc_power_good);
RCLCPP_INFO(this->get_logger(), "Motor Drive Fault 1: %d", msg->motor_drive_fault_1);
RCLCPP_INFO(this->get_logger(), "Motor Drive Fault 2: %d", msg->motor_drive_fault_2);
RCLCPP_INFO(this->get_logger(), "Motor Drive Fault 3: %d", msg->motor_drive_fault_3);
RCLCPP_INFO(this->get_logger(), "Motor Drive Fault 4: %d", msg->motor_drive_fault_4);
RCLCPP_INFO(this->get_logger(), "Board Temperature: %.2f °C", msg->board_temp);
}
rclcpp::Subscription<automatepro_interfaces::msg::IOControllerDiagnostic>::SharedPtr subscription_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<IOControllerDiagnosticSubscriber>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
Run the node using the following command:
ros2 run automatepro_cpp_tutorials io_controller_diagnostic_node