Main Content

Getting Started with uORB Blocks for PX4 Autopilots Support Package

This example shows you how to use the PX4 uORB Read and the PX4 uORB Write blocks in UAV Toolbox Support Package for PX4® Autopilots to read and write uORB messages in the uORB network.

Introduction

UAV Toolbox Support Package for PX4 Autopilots enables you to create Simulink® models that work with the uORB middleware. The uORB is an asynchronous publish() / subscribe() messaging API used for inter-thread/inter-process communication. A component sends a message by publishing it to a particular topic, such as sensor_accel. Other components receive the message by subscribing to that topic.

UAV Toolbox Support Package for PX4 Autopilots includes a library of Simulink blocks for sending and receiving messages for a specified uORB topic. When you generate code for a Simulink model containing PX4 uORB Read and PX4 uORB Write blocks and deploy it to a Pixhawk® series flight controller, the Simulink app in the controller reads data from the uORB network and also writes data to the network for the corresponding uORB topic.

In this example, you will learn how to:

  • Create Simulink models to send and receive uORB messages

  • Observe the real time uORB data by running the model in External mode

Prerequisites

Required Hardware

To run this example, you will need the following hardware:

  • Pixhawk Series flight controller

  • Micro USB type-B cable

  • Micro-SD card (already used during the initial Hardware Setup)

Task 1 - Configure and Run a Model to Read Sensor Data Using uORB Topics

In this task, you will configure a Simulink model to read sensor data from PX4 flight controller using a PX4 uORB Read block, and observe the data over External mode.

1. From the MATLAB® toolstrip, select HOME > New > Simulink Model to to open the Simulink Start Page. Click Blank Model to launch a new Simulink model.

2. On the Simulink toolbar, select View > Library Browser to open the Simulink Library Browser. Click the UAV Toolbox Support Package for PX4 Autopilots tab (you can also type px4lib in MATLAB command window). Select PX4 uORB Read and Write Blocks category.

3. Drag and drop a PX4 uORB Read block to the model.

4. Double-click the block to open the block mask. Click Select next to the "Topic to subscribe to" field. A pop-up window appears containing the msg folder of the downloaded PX4 firmware. Select SensorAccel.msg, and click Open. Click OK to close the block mask.

5. From the Simulink > Signal Routing tab in the Library Browser, drag and drop a Bus Selector block to the model.

6. Connect the Msg output of the PX4 uORB Read block to the input port of the Bus Selector block.

7. Click on Modeling > Update Model to ensure that the bus information is propagated. You may get an error: Selected signal 'signal1' in the Bus Selector block 'untitled/Bus Selector' cannot be found in the input bus signal. This error is expected, and it will be resolved in the next step.

8. Double-click the Bus Selector block. Remove signal1 and signal2 from the list of signals that are being assigned. Select x, y and z signals in the list. Click OK.

9. From the Simulink > Sinks tab in the Library Browser, drag and drop four Display blocks to the model. Connect the three outputs of the Bus Selector block to the three Display blocks. Connect the Status output to the fourth Display block. Your entire model should look like this.

10. Connect the Pixhawk series controller to the host computer using the USB cable.

11. In the Modeling tab, click Model Settings.

12. In the Configuration Parameters dialog box, navigate to the Hardware Implementation pane:

  • Set the Hardware board to the same Pixhawk series controller that you selected during Hardware Setup screens.

  • In the Target Hardware Resources section, enter the serial port of the host computer to which the Pixhawk series controller is connected, in the Serial port for firmware upload field. The Serial port for Nuttx (NSH) Terminal is optional.

13. In the Simulation tab, set the simulation Stop time to inf.

14. On the Hardware tab, in the Mode section, select Run on board and then click Monitor & Tune to start signal monitoring and parameter tuning.

Wait for the code generation to be completed. Whenever the dialog box appears instructing you to reconnect the flight controller to the serial port, ensure that you click OK on the dialog box within 5 seconds after reconnecting the flight controller.

After the Pixhawk series controller is flashed, wait for the signal monitoring to start.

Observe the accelerometer values while the simulation is running. Change the position of the board along all the axes and observe the corresponding accelerometer values along those axes.

A pre-configured Simulink model(px4demo_uORBRead) is also available, which helps you to read the accelerometer, gyroscope, and barometer values using the sensor_accel, sensor_gyro and sensor_baro uORB topics respectively. This model is configured with PX4 Host Target as the default board. When PX4 Host Target is set as the hardware board, you can perform Connected I/O simulation. When you simulate a model in Connected I/O, the model communicates with the PX4 Host Target, enabling you to read and write data to the PX4 Host Target from Simulink.

Open the px4demo_uORBRead model.

Task 2 - Create a Publisher

In this task and the two subsequent tasks (Task 3 and Task 4), you will create a complete model that consists of blocks to publish data (PX4 uORB Write) and subscribe data (PX4 uORB Read), using the VehicleGlobalPosition uORB topic.

1. From the MATLAB toolstrip, select HOME > New > Simulink Model to open a new Simulink model.

2. On the Simulink toolbar, select View > Library Browser to open the Simulink Library Browser. Click the UAV Toolbox Support Package for PX4 Autopilots tab (you can also type px4lib in MATLAB command window). Select PX4 uORB Read and Write Blocks category.

3. Drag and drop a PX4 uORB Write block to the model.

4. Double-click the block. Click Select next to the "Topic to publish to" field. A pop-up window appears containing the msg folder of the selected PX4 firmware. Select vehicle_global_position.msg, and click Open.

Click OK to close the block mask.

Task 3 - Create a Blank uORB Message

In this task, you will create a blank uORB message in the model created in Task 2, and populate the latitude (lat), longitude (lon), altitude (alt), and velocity (terrain_alt) fields for uORB topic VehicleGlobalPosition.

A uORB message is represented as a bus signal in Simulink. A bus signal is a bundle of Simulink signals, and can also include the other bus signals (see the Simulink Bus Signals example for an overview). The PX4 uORB Message block outputs a Simulink bus signal corresponding to a uORB message.

1. On the Simulink toolbar, select View > Library Browser to open the Simulink Library Browser. Click the UAV Toolbox Support Package for PX4 Autopilots tab (you can also enter the command px4lib in MATLAB command window). Select the PX4 uORB Read and Write Blocks category.

2. Drag and drop a PX4 uORB Message block to the model. Double-click the block to open the block mask.

3. Click Select next to the Topic field. A pop-up window appears containing the msg folder of the selected PX4 firmware. Select vehicle_global_position.msg, and click Open. Click OK to close the block mask.

4. From the Simulink > Signal Routing tab in the Library Browser, drag and drop a Bus Assignment block.

5. Connect the output port of the PX4 uORB Message block to the Bus input port of the Bus Assignment block. Connect the output port of the Bus Assignment block to the input port of PX4 uORB Write block.

6. Double-click on the Bus Assignment block to open the block mask. You should see lat, lon, alt and terrain_alt (the signals comprising a VehicleGlobalPosition uORB topic) listed on the left. Select ???signal1 in the list on the right, and click Remove. Select lat, lon, alt and terrain_alt signals in the list on the left, and click Select>> to move them to the right. Click OK to close the block mask.

Note: If you do not see the signals listed, close the block mask for the Bus Assignment block, and click Simulation > Update Diagram to ensure that the bus information is correctly propagated. If you see the error, Selected signal 'signal1' in the Bus Assignment block cannot be found, it indicates that the bus information has not been propagated. Close the Diagnostic Viewer, and repeat the above step.

You can now populate the bus signal with random values that represent the GPS location.

7. From the Simulink > Sources tab in the Library Browser, drag and drop four Constant blocks into the model.

8. Connect the output ports of each Constant block to the Bus Assignment input ports.

9. Double-click each of the Constant blocks that is connected to Bus Assignment, set the Constant values (as indicated in the below figure), and set the Output data type as Inherit:Inherit via back propagation.

The model should now look like this:

Task 4 - Create a Subscriber

In this task, you will add a subscriber (PX4 uORB Read block) to the model created in Task 3, to receive messages sent to the VehicleGlobalPosition topic. You will extract the lat, lon, alt and terrain_alt signals from the message.

1. From the UAV Toolbox Support Package for PX4 Autopilots tab in the Library Browser, drag and drop a PX4 uORB Read block to the model.

2. Double-click the block. Click Select next to the Topic to subscribe to field. A pop-up window appears containing the msg folder of the selected PX4 firmware. Select vehicle_global_position.msg, and click Open. Click OK to close the block mask.

The PX4 uORB Read block outputs a Simulink bus signal; so you need to extract the lat, lon, alt and terrain_alt signals from it.

3. From the Simulink > Signal Routing tab in the Library Browser, drag and drop a Bus Selector block to the model.

4. Connect the Msg output of the PX4 uORB Read block to the input port of the Bus Selector block.

5. Click on Modeling > Update Model to ensure that the bus information is propagated. You may get an error, Selected signal 'signal1' in the Bus Selector block 'untitled/Bus Selector' cannot be found in the input bus signal. This error is expected, and will be resolved by the next step.

6. Double-click the Bus Selector block. Remove signal1 and signal2 from the list of signals that are being assigned. Select lat, lon, alt and terrain_alt signals in the list. Click OK.

The PX4 uORB Read block outputs the most-recently received message for the topic on every time step. The Status output indicates whether the message has been received during the prior time step. For the current task, the Status output is not needed, and you can terminate it as explained below:

7. Click Simulink > Sinks tab in the Library Browser. Drag and drop a Terminator block to the model.

8. Connect the Status output of the PX4 uORB Read block to the input of the Terminator block.

The next step will help you to configure the display of the extracted lat, lon, alt and terrain_alt signals.

9. From the Simulink > Sinks tab in the Library Browser, drag and drop four Display blocks to the model. Connect the each output of the Bus Selector block to each Display block.

Your entire model should look like this:

10. Save the model.

Task 5 - Configure and Run the Model

In this task, you will define the configuration parameters and run the complete model (created through Tasks 2 to 4) for signal monitoring and parameter tuning.

1. Open Configuration Parameters dialog box, and set the Target Hardware as the Pixhawk Series controller that you have selected during Hardware Setup screens.

2. Enter the serial port to which the Pixhawk Series controller is connected to host computer. Click Apply and OK.

3. In the Simulation tab, set the simulation Stop time to inf.

4. On the Hardware tab, in the Mode section, select Run on board and then click Monitor & Tune to start signal monitoring and parameter tuning.

6. While the simulation is running, change the value of the constant block connected to alt field of Bus Assignment block, from 37 to 44. You can observe the corresponding change in Display block connected to alt port of the Bus Selector block.

7. Observe that the base MATLAB workspace has one or more variables whose name starts with px4_Bus_. These are temporary bus objects created by Simulink and should not be modified. However, it is safe to clear them from the workspace, as they will be re-created if needed.

8. In the Hardware tab, click Stop to stop the simulation.

A pre-configured model(px4demo_uORBReadWrite) with publish/subscribe blocks is available for your reference. This model is configured with PX4 Host Target as the default board. When PX4 Host Target is set as the hardware board, you can perform Connected I/O simulation. Open the px4demo_uORBReadWrite model.