[Documentation] [TitleIndex] [WordIndex

Interacting with the I/O module via ROS topics

About the ROS topics interface of the I/O modules drivers

The driver that controls the I/O module allows the user to interact with the module using a number of ROS topics.

These topics are provided to give the user an immediate and easy way to interact with the I/O modules. The user can read the state of a module's inputs and set the value of a module's outputs. This can be done by using the command line or by writing a python script or a C++ program.

Topics provided

The following topics can be found when the driver is running.

The names of the topics will vary depending on the etherCAT Product Code (first number) and the Serial Number of the device (second number):

   1 > rostopic list | grep device_0x
   2 /device_0x05300424_0x00000016_PWM_outputs_command
   3 /device_0x05300424_0x00000016_analog_inputs_state
   4 /device_0x05300424_0x00000016_analog_outputs_command
   5 /device_0x05300424_0x00000016_digital_inputs_state
   6 /device_0x05300424_0x00000016_digital_outputs_command

The driver is listening to those topics with names ending in _command, and is publishing to the topics with names ending in _state.

Command line usage

The user can interact with the topics using command line tools.

Set output values

Digital I/O's

The digital I/O's can be configured as inputs or outputs (or as PWM outputs) using the _digital_outputs_command topic. This topic also allows to set the output value if the pin is configured as an output.

To do this from the command line, we publish a message, consisting of an array with two boolean values for every one of the digital I/O pins. The first value determines if the pin will behave as an input or an output (true=input, false=output) the second value sets the output value if the pin is configured as an output (true=1, false=0), otherwise it is ignored.

The following command would set the pins 0, 1 and 2 as outputs and the pin 3 as input. The output values would be 1 for the pin 0 and 0 for the pins 1 and 2. Pin 3 output is not determined (as it is an input).

   1 > rostopic pub /device_0x05300424_0x00000016_digital_outputs_command sr_common_msgs/BoolArray "[false, true, false, false, false, false, true, false]"

PWM outputs

Every digital I/O pin can be configured as a PWM output. Publishing a message to the _PWM_outputs_command topic we can set the period and the ON-time of the PWM signal for every pin. If both are set to 0, the pin is not used for PWM.

To do this from the command line, we publish a message, consisting of an array with two 16 bit integer values for every one of the digital I/O pins. The first value determines the period and the second value determines the ON-time.

The period and ON-time parameters to use with this topic are the Vperiod and Von parameters described in the RoNeX User Manual.

   1 > rostopic pub /device_0x05300424_0x00000016_PWM_outputs_command std_msgs/UInt16MultiArray "{layout: {}, data: [0x8000, 0x4000, 0, 0, 0, 0, 0, 0]}"

Analogue outputs

To set the analogue output value from the command line, we publish a message, consisting of an array with a 16 bit integer value for every one of the analogue output pins.

   1 > rostopic pub /device_0x05300424_0x00000016_analog_outputs_command std_msgs/UInt16MultiArray "{layout: {}, data: [0x7000, 0xEFFF]}"

Get input values

Digital I/O's

It's worth noting that the digital I/O's can be configured as inputs or outputs, or as PWM outputs, but in any case, the value at the pin can be read back in the _digital_inputs_state topic.

   1 > rostopic echo /device_0x05300424_0x00000016_digital_inputs_state

Analogue inputs

   1 > rostopic echo /device_0x05300424_0x00000016_analog_inputs_state

Python code example

The following python code shows how to subscribe to the state topics and how to publish to the command topics to set the desired value to the outputs.

   1 import rospy
   2 
   3 from sr_common_msgs.msg import BoolArray
   4 from std_msgs.msg import UInt16MultiArray
   5 
   6 PRODUCT_CODE = "0x05300424"
   7 DEVICE_SN = "0x00000016"
   8 
   9 class IoTest(object):
  10     def __init__(self, device_SN):
  11         rospy.loginfo("Testing device. Product code: " + PRODUCT_CODE + " SN: " + device_SN)
  12 
  13         self.analog_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_analog_outputs_command", UInt16MultiArray, latch=True)
  14         self.digital_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_digital_outputs_command", BoolArray, latch=True)
  15         self.PWM_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_PWM_outputs_command", UInt16MultiArray, latch=True)
  16         self.analog_state_subscriber_ = rospy.Subscriber("/device_" + PRODUCT_CODE + "_" + device_SN + "_analog_inputs_state", UInt16MultiArray, self.analog_state_callback)
  17         self.digital_state_subscriber_ = rospy.Subscriber("/device_" + PRODUCT_CODE + "_" + device_SN + "_digital_inputs_state", BoolArray, self.digital_state_callback)
  18 
  19     def analog_state_callback(self, msg):
  20         #Do something with the received data
  21         #e.g. print the input 0
  22         rospy.loginfo("Receive data from analog input 0: %f",msg.data[0])
  23 
  24     def digital_state_callback(self, msg):
  25         #Do something with the received data
  26         #e.g. print the input 0
  27         rospy.loginfo("Receive data from digital input 0: %f",msg.data[0])
  28 
  29     def run_test(self):
  30         #Here we'll set some values for the outputs
  31 
  32         #Configure the 4 digital I/O as outputs, and set all them to 0 (False)
  33         output_values = [False, False, False, False, False, False, False, False]
  34         command_msg = BoolArray(output_values)
  35         self.digital_command_publisher.publish(command_msg)
  36 
  37         #Sleep for 5 sec (to have some to see the change)
  38         rospy.sleep(5.0)
  39 
  40         #Configure the 4 digital I/O as outputs, and set all them to 0 (False) except for the output 0, that is set to 1 (True)
  41         output_values = [False, True, False, False, False, False, False, False]
  42         command_msg = BoolArray(output_values)
  43         self.digital_command_publisher.publish(command_msg)
  44 
  45         #Sleep for 5 sec
  46         rospy.sleep(5.0)
  47 
  48         #Set a value for each of the 2 analog outputs
  49         command_msg = UInt16MultiArray(None, [0x7000, 0xEFFF])
  50         self.analog_command_publisher.publish(command_msg)
  51 
  52         #Sleep for 5 sec
  53         rospy.sleep(5.0)
  54 
  55         #Set the digital I/O pin 0 as a PWM output with a period of 0x8000 and an ON-time of 0x4000 (the other 3 are not used as PWM here)
  56         command_msg = UInt16MultiArray(None, [0x8000, 0x4000, 0, 0, 0, 0, 0, 0])
  57         self.PWM_command_publisher.publish(command_msg)
  58 
  59         rospy.spin()
  60 
  61 if __name__ == '__main__':
  62     io_test = IoTest(DEVICE_SN)
  63     io_test.run_test()

2024-11-09 17:39