diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile new file mode 100644 index 00000000..948629f4 --- /dev/null +++ b/.devcontainer/Dockerfile @@ -0,0 +1,31 @@ +#------------------------------------------------------------------------------------------------------------- +# Copyright (c) Microsoft Corporation. All rights reserved. +# Licensed under the MIT License. See https://go.microsoft.com/fwlink/?linkid=2090316 for license information. +#------------------------------------------------------------------------------------------------------------- + +# To fully customize the contents of this image, use the following Dockerfile instead: +# https://github.com/microsoft/vscode-dev-containers/tree/v0.106.0/containers/ubuntu-18.04-git/.devcontainer/Dockerfile +FROM mcr.microsoft.com/vscode/devcontainers/base:0-ubuntu-18.04 + +ENV DEBIAN_FRONTEND=noninteractive +RUN apt-get update \ + && apt-get -y install --no-install-recommends build-essential ruby ruby-dev locales zlib1g-dev \ + && gem install bundler \ + # + # Clean up + && apt-get autoremove -y \ + && apt-get clean -y \ + && rm -rf /var/lib/apt/lists/* + +RUN echo "en_US UTF-8" > /etc/locale.gen \ + && locale-gen en_US.UTF-8 + +ENV LANG=en_US.UTF-8 +ENV LANGUAGE=en_US:en +ENV LC_ALL=en_US.UTF-8 +ENV DEBIAN_FRONTEND=dialog + +# TEST COMMANDS: +# bundle install +# bundle exec jekyll serve + diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 00000000..6cfca0bb --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,30 @@ +// For format details, see https://aka.ms/vscode-remote/devcontainer.json or this file's README at: +// https://github.com/microsoft/vscode-dev-containers/tree/v0.106.0/containers/ubuntu-18.04-git +{ + "name": "Ubuntu 18.04 & Git", + "dockerFile": "Dockerfile", + + // Set *default* container specific settings.json values on container create. + "settings": { + "terminal.integrated.shell.linux": "/bin/bash" + }, + + // Add the IDs of extensions you want installed when the container is created. + "extensions": [] + + // Use 'forwardPorts' to make a list of ports inside the container available locally. + // "forwardPorts": [], + + // Use 'postCreateCommand' to run commands after the container is created. + // "postCreateCommand": "uname -a", + + // Uncomment to use the Docker CLI from inside the container. See https://aka.ms/vscode-remote/samples/docker-in-docker. + // "mounts": [ "source=/var/run/docker.sock,target=/var/run/docker.sock,type=bind" ], + + // Uncomment when using a ptrace-based debugger like C++, Go, and Rust + // "runArgs": [ "--cap-add=SYS_PTRACE", "--security-opt", "seccomp=unconfined" ], + "runArgs": [ "--net=host"], + + // Uncomment to connect as a non-root user. See https://aka.ms/vscode-remote/containers/non-root. + // "remoteUser": "vscode" +} \ No newline at end of file diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index c58579f6..742791b0 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -12,6 +12,8 @@ jobs: steps: - uses: actions/checkout@v1 + with: + submodules: true - name: Set up Ruby 2.7 uses: actions/setup-ruby@v1 diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 00000000..ee0e3e9e --- /dev/null +++ b/.gitmodules @@ -0,0 +1,8 @@ +[submodule "_includes/crazyflie_demo"] + path = _includes/crazyflie_demo + url = https://github.com/micro-ROS/micro-ROS_crazyflie_demo + branch = master +[submodule "_includes/sensors_demo"] + path = _includes/sensors_demo + url = https://github.com/micro-ROS/micro-ROS_sensors_demo + branch = master diff --git a/_data/docs.yml b/_data/docs.yml index 6dc09caa..fc30773f 100644 --- a/_data/docs.yml +++ b/_data/docs.yml @@ -48,18 +48,18 @@ - title: Demos docs: - tutorials/demos/kobuki_demo + - tutorials/demos/crazyflie_demo - tutorials/demos/tof_demo - tutorials/demos/fiware_demo - - tutorials/demos/crazyflie_demo - tutorials/demos/complete_demo - title: Advanced Tutorials with Nuttx docs: - tutorials/advanced/nuttx/nuttx_getting_started + - tutorials/advanced/nuttx/add_a_microros_application - tutorials/advanced/nuttx/debugging_gdb_openocd - tutorials/advanced/nuttx/debugging_vscode - tutorials/advanced/nuttx/6lowpan_nuttx_rpi - - tutorials/advanced/nuttx/tracing - tutorials/advanced/nuttx/microros_nuttx_bsp - tutorials/advanced/nuttx/microros_6lowpan_tutorial @@ -70,4 +70,10 @@ - title: Advanced Tutorials with Zephyr docs: - tutorials/advanced/zephyr/zephyr_getting_started + - tutorials/advanced/zephyr/zephyr_emulator + +- title: Advanced Tutorials with Linux + docs: + - tutorials/advanced/linux/linux_getting_started + - tutorials/advanced/linux/tracing diff --git a/_docs/concepts/rtos/comparison/index.md b/_docs/concepts/rtos/comparison/index.md index a639495e..8f305524 100644 --- a/_docs/concepts/rtos/comparison/index.md +++ b/_docs/concepts/rtos/comparison/index.md @@ -28,59 +28,59 @@ Key questions: Table: -| **OS** | [NuttX](http://nuttx.org/) | [FreeRTOS](https://sourceforge.net/projects/freertos/) | [Zephyr](https://www.zephyrproject.org/) | -|--------------------------------------------------------------|---------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------| -| **Feature** | | | | -| **Standardization** | | | | -| POSIX | yes | partial | partial | -| POSIX.1 1 | [yes](http://nuttx.org/) | [wrapper](https://interactive.freertos.org/hc/en-us/community/posts/210029046-POSIX-Wrapper-for-FreeRTOS) | partial | -| POSIX.1b 2 | yes | partial | partial | -| POSIX.1c 3 | yes | yes | partial | -| | | | | -| OSEK/VDX | no | no | no | -| **Maturity** | | | | -| First release | 2007 | 2014 | 2016 | -| Last release | 2019 | 2019 | 2019 | -| Update rate | about 3 months | irregular | 3 months | -| Community | open-source | open-source | Linux Foundation Collaboration Project, (Intel, Linaro (ARM), nordic, NXP, Synopsys) | -| | | | | -| **Supported Hardware** | | | | -| Olimex STM32-E407 (Cortex-M4) | yes | yes | yes, [explicitly](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) | -| Bosch XDK 5 | not explicitly, but similar 6 | yes | yes, [explicitly](https://github.com/zephyrproject-rtos/zephyr/blob/master/ext/hal/README) | -| MPC57xx | no | no | no | -| **Scheduling** | | | | -| Priority-based | FIFO | yes | yes | -| Round-Robin 4 | yes | yes 6 | [co-operative](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) | -| Sporadic Server | yes | no | no | -| RBS | no | ? | no | -| Semaphore /Mutex Management | yes (Priority Inheritance) | yes | yes | -| **IO** | | | | -| I2C | yes | vendor-specific | yes | -| SPI | yes | vendor-specific | yes | -| UART | hw-specific | vendor-specific | yes | -| USB | yes | vendor-specific | yes | -| CAN | yes | vendor-specific | yes | -| CAnopen | no | vendor-specific | yes | -| Modbus | yes | vendor-specific | ? | -| **Networking** 7 | | | | -| BLE-Stack | unclear | no | yes | -| 6LoWPAN | yes | no | yes | -| TLS | | yes | yes | -| Thread | | ? | ? | -| Ethernet | yes | no | yes | -| Wifi | yes | no | yes | -| NFC | unclear | no | yes | -| RFID | yes | no | yes | -| **Storage & Display** 7 | | | | -| File System | yes | ? | yes | -| Graphical User Interface | | ? | ? | -| **Memory Footprint** | | | | -| RAM | "small footprint" | 236 B scheduler + 64 B / task | "small footprint" | -| ROM | "small footprint" | 5 - 10 kB | "small footprint" | -| **Safety Certification** | | | | -| Software Development Process DO178B Level A / EUROCAE ED-12B | no | [SafeRTOS: DO178C (Aerspace) by Wittenstein](https://www.highintegritysystems.com/safertos/certification-and-standards/) | no | -| Functional Safety IEC-61508 | no | [SafeRTOS (SIL 3)](https://www.freertos.org/FreeRTOS-Plus/Safety_Critical_Certified/SafeRTOS.shtml) | soon | -| **License** | BSD | MIT and Commercial | Apache 2 | +| **OS** | [NuttX](http://nuttx.org/) | [FreeRTOS](https://sourceforge.net/projects/freertos/) | [Zephyr](https://www.zephyrproject.org/) | +| ------------------------------------------------------------ | ---------------------------------------- | ------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------------------------------------- | +| **Feature** | | | | +| **Standardization** | | | | +| POSIX | yes | partial | partial | +| POSIX.1 1 | [yes](http://nuttx.org/) | [wrapper](https://interactive.freertos.org/hc/en-us/community/posts/210029046-POSIX-Wrapper-for-FreeRTOS) | partial | +| POSIX.1b 2 | yes | partial | partial | +| POSIX.1c 3 | yes | yes | partial | +| | | | | +| OSEK/VDX | no | no | no | +| **Maturity** | | | | +| First release | 2007 | 2014 | 2016 | +| Last release | 2019 | 2019 | 2019 | +| Update rate | about 3 months | irregular | 3 months | +| Community | open-source | open-source | Linux Foundation Collaboration Project, (Intel, Linaro (ARM), nordic, NXP, Synopsys) | +| | | | | +| **Supported Hardware** | | | | +| Olimex STM32-E407 (Cortex-M4) | yes | yes | yes, [explicitly](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) | +| Bosch XDK 5 | not explicitly, but similar 6 | yes | yes | +| MPC57xx | no | no | no | +| **Scheduling** | | | | +| Priority-based | FIFO | yes | yes | +| Round-Robin 4 | yes | yes 6 | [co-operative](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) | +| Sporadic Server | yes | no | no | +| RBS | no | ? | no | +| Semaphore /Mutex Management | yes (Priority Inheritance) | yes | yes | +| **IO** | | | | +| I2C | yes | vendor-specific | yes | +| SPI | yes | vendor-specific | yes | +| UART | hw-specific | vendor-specific | yes | +| USB | yes | vendor-specific | yes | +| CAN | yes | vendor-specific | yes | +| CAnopen | no | vendor-specific | yes | +| Modbus | yes | vendor-specific | ? | +| **Networking** 7 | | | | +| BLE-Stack | unclear | no | yes | +| 6LoWPAN | yes | no | yes | +| TLS | | yes | yes | +| Thread | | ? | ? | +| Ethernet | yes | no | yes | +| Wifi | yes | no | yes | +| NFC | unclear | no | yes | +| RFID | yes | no | yes | +| **Storage & Display** 7 | | | | +| File System | yes | ? | yes | +| Graphical User Interface | | ? | ? | +| **Memory Footprint** | | | | +| RAM | "small footprint" | 236 B scheduler + 64 B / task | "small footprint" | +| ROM | "small footprint" | 5 - 10 kB | "small footprint" | +| **Safety Certification** | | | | +| Software Development Process DO178B Level A / EUROCAE ED-12B | no | [SafeRTOS: DO178C (Aerspace) by Wittenstein](https://www.highintegritysystems.com/safertos/certification-and-standards/) | no | +| Functional Safety IEC-61508 | no | [SafeRTOS (SIL 3)](https://www.freertos.org/FreeRTOS-Plus/Safety_Critical_Certified/SafeRTOS.shtml) | soon | +| **License** | BSD | MIT and Commercial | Apache 2 | 1 Processes, signals, fpe, segmentation, bus errors, timers, file and directory ops, pipes, c library, IO Port Interface diff --git a/_docs/overview/hardware/imgs/2.jpg b/_docs/overview/hardware/imgs/2.jpg new file mode 100644 index 00000000..58c0453f Binary files /dev/null and b/_docs/overview/hardware/imgs/2.jpg differ diff --git a/_docs/overview/hardware/imgs/3.jpg b/_docs/overview/hardware/imgs/3.jpg new file mode 100644 index 00000000..d0900fdd Binary files /dev/null and b/_docs/overview/hardware/imgs/3.jpg differ diff --git a/_docs/overview/hardware/index.md b/_docs/overview/hardware/index.md index 9521a3bf..1ef76f26 100644 --- a/_docs/overview/hardware/index.md +++ b/_docs/overview/hardware/index.md @@ -3,7 +3,7 @@ title: Supported Hardware permalink: /docs/overview/hardware/ --- -By default, micro-ROS uses [NuttX RTOS](https://nuttx.org/). This RTOS has a big variety of supported MCUs and development boards. The next list shows some of them: +micro-ROS targets mid-range and high-performance 32-bits microcontrollers families. For now, most of the ports are based on the [STM32 series](https://www.st.com/en/microcontrollers-microprocessors/stm32-32-bit-arm-cortex-mcus.html) from ST. These kinds of MCU feature ARM Cortex-M processors with many peripherals such as GPIO, communication or coprocessors. By default, micro-ROS uses [NuttX RTOS](https://nuttx.org/), but it also has ports for [FreeRTOS](https://www.freertos.org/) and [Zephyr](https://www.zephyrproject.org/). These RTOSes have a big variety of supported MCUs and development boards. The follwing list shows some of them: + MicroChip PIC32MX Family + Atmel SAMA5Dx @@ -11,11 +11,16 @@ By default, micro-ROS uses [NuttX RTOS](https://nuttx.org/). This RTOS has a big + Renesas M16C/26 + NXP/Freescale i.MX1/6 and i.MX RT + Silicon Labs EFM32 Gecko and Giant Gecko ++ XTENSA board, that includes ESP32 ++ RISC-V boards -Please check [this link](https://cwiki.apache.org/confluence/display/NUTTX/Supported+Platforms) to check the complete list and the status of each board. In case you are interested in porting new boards or MCUs, please check the [next link](https://cwiki.apache.org/confluence/display/NUTTX/Porting+Guide). + +Please check [this link](https://cwiki.apache.org/confluence/display/NUTTX/Supported+Platforms) to see the complete list and the status of each board. In case you are interested in porting new boards or MCUs, please check the [next link](https://cwiki.apache.org/confluence/display/NUTTX/Porting+Guide). Even though many development boards could be used, we have chosen two of them as references. This page lists the hardware platforms that we use to test and develop micro-ROS, and also accessories that we frequently refer to, such as add-on boards, and JTAG probes. +For the ease of use, micro-ROS provides a ready to use example for some development boards. These out-of-the-box examples aim to show micro-ROS capabilities and they are also a starting point for developing embedded ROS 2 applications. + ## Reference Platforms {#evaluation-boards} This section describes the main characteristic of the selected boards. @@ -26,11 +31,16 @@ This section describes the main characteristic of the selected boards. The [Olimex LTD STM32-E407](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware) is an open-hardware low-cost entry board for developing custom applications with the STM32F407ZGT6 Cortex-M4F microcontrollers from STMicroelectronics. -It contains 196KB of RAM and 1MB of Flash. It is a very complete board thanks to the wide variety of communication interfaces it offers: USB OTG, Ethernet, SD Card slot, SPI, CAN or I2C buses are exposed. The board contains various expansion options available: Arduino-like headers for attaching daughter boards, many pins exposed, as well as a UEXT connector. This connector is a custom pin-out bus and is used to attach sensor breakouts sensors that manufacturer sells. +It contains 196KB of RAM and 1MB of Flash. It is a very complete board thanks to the wide variety of communication interfaces it offers: USB OTG, Ethernet, SD Card slot, SPI, CAN or I2C buses are exposed. The board contains various expansion options available: Arduino-like headers for attaching daughter boards, many pins exposed, as well as a UEXT connector. This connector is a custom pin-out bus and is used to attach sensor breakouts that manufacturer sells. + +Ports for micro-ROS on all supported RTOS are available for this board. Examples on how to start developing with this board are available: + - [Zephyr](/docs/tutorials/advanced/zephyr/zephyr_getting_started/) + - [Nuttx](/docs/tutorials/advanced/nuttx/nuttx_getting_started/) + - [FreeRTOS](/docs/tutorials/advanced/freertos/freertos_getting_started/) ### Development tools -In order to flash and debug the board, it is required to get a JTAG probe. We recommend getting on of the next JTAG probes: +In order to flash and debug the board, it is required to get a JTAG probe. We recommend getting one of the following JTAG probes: + [ARM-USB-OCD-H](https://www.olimex.com/Products/ARM/JTAG/ARM-USB-OCD-H/) + [ARM-USB-TINY-H](https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H/) @@ -55,3 +65,51 @@ The (STM32L1 Discovery Kit)[https://www.st.com/en/evaluation-tools/32l152cdiscov + [Schematics in PDF](https://www.st.com/resource/en/schematic_pack/32l152cdiscovery_sch.zip) + [Bill of Material](https://www.st.com/resource/en/bill_of_materials/32l152cdiscovery_bom.zip) + [Gerber files](https://www.st.com/resource/en/bill_of_materials/32l152cdiscovery_bom.zip) + + +## STM32L4 Discovery kit IoT + +The [ST B-L475E-IOT01A](https://www.st.com/en/evaluation-tools/b-l475e-iot01a.html) evaluation board is a ready to use IoT kit. This board supports an out-of-the-box micro-ROS + Zephyr port. + + + +The STM32L4 Discovery kit IoT enables a wide diversity of applications by exploiting low-power communication, multiway sensing and Arm Cortex M4 core-based STM32L4 Series features. +The support for Arduino and PMOD connectivity provides unlimited expansion capabilities with a large choice of specialized add-on boards. + +This board features a STM32L475E MCU with 1 MB of Flash memory and 128 KB of RAM. In addition to the MCU peripherals, the board includes: + - 64 Mb SPI Flash memory + - Bluetooth V4.1 module (SPBTLE-RF) + - 915 MHz low-power RF module (SPSGRF-915) + - 802.11 b/g/n module (ISM43362-M3G-L44) + - NFC tag based on M24SR with printed antenna + - 2 digital microphones (MP34DT01) + - relative humidity and temperature digital sensor (HTS221) + - 3-axis magnetometer (LIS3MDL) + - 3-axis accelerometer and gyroscope (LSM6DSL) + - digital barometer (LPS22HB) + - Time-of-Flight and gesture-detection sensor (VL53L0X) + - programmable push-buttons + - USB OTG FS with Micro-AB connector + - on-board ST-LINK/V2 debugger and programmer + +Examples on how to start developing with this board are available [here](/docs/tutorials/demos/tof_demo/). + + +## Crazyflie 2.1 Drone + +As an integration example, the open-source [Crazyflie 2.1](https://www.bitcraze.io/products/crazyflie-2-1/) platform has its own micro-ROS + FreeRTOS port. + + + +The Crazyflie 2.1 is a versatile open-source flying development platform that only weighs 27g and fits in the palm of your hand. Crazyflie 2.1 is equipped with multiple inertial sensors and low-latency/long-range radio as well as Bluetooth LE. + +This little drone features a STM32F405 ARM Cortex-M4 MCU running up to 168 MHz with 1 MB of Flash and 192 KB of RAM. It also features the following sensors and coprocessors: + - nRF51822 radio and power management MCU (Cortex-M0, 32Mhz, 16kb SRAM, 128kb flash) + - USB + - LiPo battery charger + - 8KB EEPROM + - 3-axis accelerometer and gyroscope (BMI088) + - pressure sensor (BMP388) + - headers with peripheral access: SPI, I2C, UART, 1-wire and GPIO + +Examples on how to start developing with this board are available [here](/docs/tutorials/demos/crazyflie_demo/). diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/1.jpg b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/1.jpg new file mode 100644 index 00000000..a1329cda Binary files /dev/null and b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/1.jpg differ diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/2.jpg b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/2.jpg new file mode 100644 index 00000000..962d5666 Binary files /dev/null and b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/2.jpg differ diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/3.jpg b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/3.jpg new file mode 100644 index 00000000..fe1055b1 Binary files /dev/null and b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/3.jpg differ diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/4.png b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/4.png new file mode 100644 index 00000000..6319acdc Binary files /dev/null and b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/4.png differ diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/5.jpg b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/5.jpg new file mode 100644 index 00000000..f74ee208 Binary files /dev/null and b/_docs/tutorials/advanced/freertos/freertos_getting_started/imgs/5.jpg differ diff --git a/_docs/tutorials/advanced/freertos/freertos_getting_started/index.md b/_docs/tutorials/advanced/freertos/freertos_getting_started/index.md index bf1d2836..7471702b 100644 --- a/_docs/tutorials/advanced/freertos/freertos_getting_started/index.md +++ b/_docs/tutorials/advanced/freertos/freertos_getting_started/index.md @@ -3,4 +3,397 @@ title: FreeRTOS Getting Started permalink: /docs/tutorials/advanced/freertos/freertos_getting_started/ --- -WIP \ No newline at end of file +This tutorial aims to create a new micro-ROS application on **[Olimex STM32-E407](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware)** evaluation board with **[FreeRTOS RTOS](https://www.freertos.org/)** + +
+ + + +
+ +## Required hardware + +This tutorial uses the following hardware: + +| Item | | +|---------------|----------------------------------------------------------| +| Olimex STM32-E407 | [Link](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware) | +| Olimex ARM-USB-TINY-H | [Link](https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H/) | +| USB-Serial Cable Female | [Link](https://www.olimex.com/Products/Components/Cables/USB-Serial-Cable/USB-Serial-Cable-F/) | + + +## Adding a new micro-ROS app + +First of all, make sure that you have a **ROS 2** installation. + +***TIP:** if you are familiar with Docker containers, this image may be useful: [ros:dashing](https://hub.docker.com/layers/ros/library/ros/dashing/images/sha256-b796c14ea663537129897769aa6c715a851ca08dffd4875ef2ecaa31a4dbd431?context=explore)* + +On the **ROS 2** installation open a command line and follow these steps: + +```bash +# Source the ROS 2 installation +source /opt/ros/$ROS_DISTRO/setup.bash + +# Create a workspace and download the micro-ROS tools +mkdir microros_ws +cd microros_ws +git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build + +# Update dependencies using rosdep +rosdep update +rosdep install --from-path src --ignore-src -y + +# Build micro-ROS tools and source them +colcon build +source install/local_setup.bash +``` + + +Now, let's create a firmware workspace that targets all the required code and tools for Olimex development board and FreeRTOS: + +```bash +# Create step +ros2 run micro_ros_setup create_firmware_ws.sh freertos olimex-stm32-e407 +``` + +Now you have all the required tools to crosscompile micro-ROS and FreeRTOS for Olimex STM32-E407 development board. At this point, you must know that the micro-ROS build system is a four-step workflow: + + +1. **Create**: retrieves all the required packages for a specific RTOS and hardware platform. +2. **Configure**: configures the downloaded packages with options such as the micro-ROS application, the selected transport layer or the micro-ROS agent IP address (in network transports). +3. **Build**: generates a binary file ready for being loaded in the hardware. +4. **Flash**: load the micro-ROS software in the hardware. + +micro-ROS apps for Olimex + FreeRTOS are located at `firmware/freertos_apps/apps`. In order to create a new application, create a new folder containing two files: the app code and the RMW configuration. + +```bash +# Creating a new app +pushd firmware/freertos_apps/apps +mkdir my_brand_new_app +cd my_brand_new_app +touch app.c app-colcon.meta +popd +``` + +For this example we are going to create a ping pong app where a node sends a ping package with a unique identifier using a publisher and the same package is received by a pong subscriber. The node will also answer to pings received from other nodes with a pong message: + +![pingpong](http://www.plantuml.com/plantuml/png/ZOwnIWGn48RxFCNFzSkoUG2vqce5jHEHi1dtWZkPa6GByNntavZY10yknMJu-ORlFwPiOjvvK-d3-M2YOR1uMKvHc93ZJafvoMML07d7h1NAE-DPWblg_na8vnwEx9OeZmzFOt1-BK7AzetJciPxCfRYVw1S0SbRLBEg1IpXPIvpUWLCmZpXIm6BS3addt7uQpu0ZQlxT1MK2r0g-7sfqbsbRrVfMrMwgbev3CDTlsqJGtJhATUmSMrMg5TKwaZUxfcttuMt7m00) + +To start creating this app, let's configure the RMW with the required static memory. You can read more about RMW and Micro XRCE-DDS Configuration [here](/docs/tutorials/core/microxrcedds_rmw_configuration/) The `app-colcon.meta` should look like: + +``` +{ + "names": { + "rmw_microxrcedds": { + "cmake-args": [ + "-DRMW_UXRCE_MAX_NODES=1", + "-DRMW_UXRCE_MAX_PUBLISHERS=2", + "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=2", + "-DRMW_UXRCE_MAX_SERVICES=0", + "-DRMW_UXRCE_MAX_CLIENTS=0", + "-DRMW_UXRCE_MAX_HISTORY=4", + ] + } + } +} +``` + +Meanwhile `app.c` should look like the following code: + +```c +#include + +#include +#include +#include +#include "rosidl_generator_c/string_functions.h" +#include + +#include + +#include +#include +#include + +#define STRING_BUFFER_LEN 100 + +// FreeRTOS thread for triggering a publication guard condition +void * trigger_guard_condition(void *args){ + rcl_guard_condition_t * guard_condition = (rcl_guard_condition_t *)args; + + while(true){ + rcl_trigger_guard_condition(guard_condition); + sleep(5); + } +} + +// App main function +void appMain(void *argument) +{ + //Init RCL options + rcl_init_options_t options = rcl_get_zero_initialized_init_options(); + rcl_init_options_init(&options, rcl_get_default_allocator()); + + // Init RCL context + rcl_context_t context = rcl_get_zero_initialized_context(); + rcl_init(0, NULL, &options, &context); + + // Create a node + rcl_node_options_t node_ops = rcl_node_get_default_options(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_init(&node, "pingpong_node", "", &context, &node_ops); + + // Create a reliable ping publisher + rcl_publisher_options_t ping_publisher_ops = rcl_publisher_get_default_options(); + rcl_publisher_t ping_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&ping_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_publisher_ops); + + // Create a best effort pong publisher + rcl_publisher_options_t pong_publisher_ops = rcl_publisher_get_default_options(); + pong_publisher_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_publisher_t pong_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&pong_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_publisher_ops); + + // Create a best effort pong subscriber + rcl_subscription_options_t pong_subscription_ops = rcl_subscription_get_default_options(); + pong_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t pong_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&pong_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_subscription_ops); + + // Create a best effort ping subscriber + rcl_subscription_options_t ping_subscription_ops = rcl_subscription_get_default_options(); + ping_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t ping_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&ping_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_subscription_ops); + + // Create a guard condition + rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); + rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options(); + rcl_guard_condition_init(&guard_condition, &context, guard_condition_options); + + // Create a thread that triggers the guard condition + pthread_t guard_condition_thread; + pthread_create(&guard_condition_thread, NULL, trigger_guard_condition, &guard_condition); + + // Create a wait set + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_wait_set_init(&wait_set, 2, 1, 0, 0, 0, 0, &context, rcl_get_default_allocator()); + + // Create and allocate the pingpong publication message + std_msgs__msg__Header msg; + char msg_buffer[STRING_BUFFER_LEN]; + msg.frame_id.data = msg_buffer; + msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Create and allocate the pingpong subscription message + std_msgs__msg__Header rcv_msg; + char rcv_buffer[STRING_BUFFER_LEN]; + rcv_msg.frame_id.data = rcv_buffer; + rcv_msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Set device id and sequence number; + int device_id = rand(); + int seq_no; + + int pong_count = 0; + struct timespec ts; + rcl_ret_t rc; + + do { + // Clear and set the waitset + rcl_wait_set_clear(&wait_set); + + size_t index_pong_subscription; + rcl_wait_set_add_subscription(&wait_set, &pong_subscription, &index_pong_subscription); + + size_t index_ping_subscription; + rcl_wait_set_add_subscription(&wait_set, &ping_subscription, &index_ping_subscription); + + size_t index_guardcondition; + rcl_wait_set_add_guard_condition(&wait_set, &guard_condition, &index_guardcondition); + + // Run session for 100 ms + rcl_wait(&wait_set, RCL_MS_TO_NS(100)); + + // Check if it is time to send a ping + if (wait_set.guard_conditions[index_guardcondition]) { + // Generate a new random sequence number + seq_no = rand(); + sprintf(msg.frame_id.data, "%d_%d", seq_no, device_id); + msg.frame_id.size = strlen(msg.frame_id.data); + + // Fill the message timestamp + clock_gettime(CLOCK_REALTIME, &ts); + msg.stamp.sec = ts.tv_sec; + msg.stamp.nanosec = ts.tv_nsec; + + // Reset the pong count and publish the ping message + pong_count = 0; + rcl_publish(&ping_publisher, (const void*)&msg, NULL); + // printf("Ping send seq 0x%x\n", seq_no); + } + + // Check if some pong message is received + if (wait_set.subscriptions[index_pong_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_pong_subscription], &rcv_msg, NULL, NULL); + + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) == 0) { + pong_count++; + // printf("Pong for seq 0x%x (%d)\n", seq_no, pong_count); + } + } + + // Check if some ping message is received and pong it + if (wait_set.subscriptions[index_ping_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_ping_subscription], &rcv_msg, NULL, NULL); + + // Dont pong my own pings + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) != 0){ + // printf("Ping received with seq 0x%x (%d). Answering.\n", seq_no); + rcl_publish(&pong_publisher, (const void*)&rcv_msg, NULL); + } + } + + usleep(10000); + } while (true); +} +``` + +Once the new folder is created, let's configure our new app with a serial transport on UART 3: + +```bash +# Configure step +ros2 run micro_ros_setup configure_firmware.sh my_brand_new_app --transport serial --dev 3 +``` + +When the configuring step ends, just build the firmware: + +```bash +# Build step +ros2 run micro_ros_setup build_firmware.sh +``` + +Once the build has successfully ended, let's power and connect the board. First, connect Olimex ARM-USB-TINY-H JTAG programmer to the board's JTAG port: + + + +Make sure that the board power supply jumper (PWR_SEL) is in the 3-4 position in order to power the board from the JTAG connector: + + + +You should see the red LED lighting. It is time to flash the board: + +```bash +# Flash step +ros2 run micro_ros_setup flash_firmware.sh +``` +## Running the micro-ROS app + +The micro-ROS app is ready to connect to a micro-ROS-Agent and start talking with the rest of the ROS 2 world. + +First of all, create and build a micro-ROS agent: + +```bash +# Download micro-ROS-Agent packages +ros2 run micro_ros_setup create_agent_ws.sh + +# Build micro-ROS-Agent packages, this may take a while. +colcon build --metas src +source install/local_setup.bash +``` + +Then connect the Olimex development board to the computer using the usb to serial cable: + + + +***TIP:** Color codes are applicable to [this cable](https://www.olimex.com/Products/Components/Cables/USB-Serial-Cable/USB-Serial-Cable-F/). Make sure to match Olimex Rx with Cable Tx and vice-versa. Remember GND!* + +Then run the agent: + +```bash +# Run a micro-ROS agent +ros2 run micro_ros_agent micro_ros_agent serial --dev [device] +``` + +***TIP:** you can use this command to find your serial device name: `ls /dev/serial/by-id/*`* + +And finally, let's check that everything is working in a new command line. We are going to listen to ping topic to check whether the Ping Pong node is publishing its own pings + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS ping topic +ros2 topic echo /microROS/ping +``` + +You should see the topic messages published by the Ping Pong node every 5 seconds: + +``` +pgarrido@pgarrido:~$ ros2 topic echo /microROS/ping +stamp: + sec: 20 + nanosec: 867000000 +frame_id: '1344887256_1085377743' +--- +stamp: + sec: 25 + nanosec: 942000000 +frame_id: '730417256_1085377743' +--- +``` + +On another command line, let's subscribe to the pong topic + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS pong topic +ros2 topic echo /microROS/pong +``` + +At this point, we know that our app is publishing pings. Let's check if it also answers to someone else pings in a new command line: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Send a fake ping +ros2 topic pub --once /microROS/ping std_msgs/msg/Header '{frame_id: "fake_ping"}' +``` + +Now, we should see on the ping subscriber our fake ping along with the board pings: + +``` +pgarrido@pgarrido:~$ ros2 topic echo /microROS/ping +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +stamp: + sec: 305 + nanosec: 973000000 +frame_id: '451230256_1085377743' +--- +stamp: + sec: 310 + nanosec: 957000000 +frame_id: '2084670932_1085377743' +--- +``` + +And in the pong subscriber, we should see the board's answer to our fake ping: + +``` +pgarrido@pgarrido:~$ ros2 topic echo /microROS/pong +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +``` + + + + + + diff --git a/_docs/tutorials/advanced/linux/linux_getting_started/index.md b/_docs/tutorials/advanced/linux/linux_getting_started/index.md new file mode 100644 index 00000000..be019371 --- /dev/null +++ b/_docs/tutorials/advanced/linux/linux_getting_started/index.md @@ -0,0 +1,392 @@ +--- +title: Linux Getting Started +permalink: /docs/tutorials/advanced/linux/linux_getting_started/ +--- + +This tutorial aims to create a new micro-ROS application on Linux for testing purposes. + +## Adding a new micro-ROS app + +First of all, make sure that you have a **ROS 2** installation. + +***TIP:** if you are familiar with Docker containers, this image may be useful: [ros:dashing](https://hub.docker.com/layers/ros/library/ros/dashing/images/sha256-b796c14ea663537129897769aa6c715a851ca08dffd4875ef2ecaa31a4dbd431?context=explore)* + +On the **ROS 2** installation open a command line and follow these steps: + +```bash +# Source the ROS 2 installation +source /opt/ros/$ROS_DISTRO/setup.bash + +# Create a workspace and download the micro-ROS tools +mkdir microros_ws +cd microros_ws +git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build + +# Update dependencies using rosdep +sudo apt update && rosdep update +rosdep install --from-path src --ignore-src -y + +# Build micro-ROS tools and source them +colcon build +source install/local_setup.bash +``` + +Now, let's create a firmware workspace that targets all the required code and tools: + +```bash +# Create step +ros2 run micro_ros_setup create_firmware_ws.sh host +``` + +Now you have all the required tools to build micro-ROS. At this point, you must know that the micro-ROS build system is a four-step workflow: + + +1. **Create**: retrieves all the required packages for a specific RTOS and hardware platform. +2. **Configure**: configures the downloaded packages with options such as the micro-ROS application, the selected transport layer or the micro-ROS agent IP address (in network transports). +3. **Build**: generates a binary file ready for being loaded in the hardware. +4. **Flash**: load the micro-ROS software in the hardware. + +micro-ROS apps for Linux are located at `src/uros/micro-ROS-demos/rcl/`. In order to create a new application, create a new folder containing two files: the app code and the CMake file. + +```bash +# Creating a new app +pushd src/uros/micro-ROS-demos/rcl/ +mkdir my_brand_new_app +cd my_brand_new_app +touch app.c CMakeLists.txt +popd +``` + +For this example we are going to create a ping pong app where a node sends a ping package with a unique identifier using a publisher and the same package is received by a pong subscriber. The node will also answer to pings received from other nodes with a pong message: + +![pingpong](http://www.plantuml.com/plantuml/png/ZOwnIWGn48RxFCNFzSkoUG2vqce5jHEHi1dtWZkPa6GByNntavZY10yknMJu-ORlFwPiOjvvK-d3-M2YOR1uMKvHc93ZJafvoMML07d7h1NAE-DPWblg_na8vnwEx9OeZmzFOt1-BK7AzetJciPxCfRYVw1S0SbRLBEg1IpXPIvpUWLCmZpXIm6BS3addt7uQpu0ZQlxT1MK2r0g-7sfqbsbRrVfMrMwgbev3CDTlsqJGtJhATUmSMrMg5TKwaZUxfcttuMt7m00) + +To start creating this app, the `CMakeLists.txt` file should looks like: + +```cmake +cmake_minimum_required(VERSION 3.5) + +project(my_brand_new_app LANGUAGES C) + +find_package(ament_cmake REQUIRED) +find_package(rcl REQUIRED) +find_package(std_msgs REQUIRED) +find_package(rmw_microxrcedds REQUIRED) + +add_executable(${PROJECT_NAME} app.c) + +ament_target_dependencies(${PROJECT_NAME} + rcl + std_msgs + rmw_microxrcedds + ) + +install(TARGETS ${PROJECT_NAME} + DESTINATION ${PROJECT_NAME} + ) +``` + +Meanwhile `app.c` should look like the following code: + +```c +#include +#include +#include + +#include + +#include +#include +#include + +#define STRING_BUFFER_LEN 100 + +// Publishing ping guard condition thread +void * trigger_guard_condition(void *args){ + rcl_guard_condition_t * guard_condition = (rcl_guard_condition_t *)args; + + while(true){ + rcl_trigger_guard_condition(guard_condition); + sleep(5); + } +} + +int main(int argc, const char * const * argv) +{ + //Init RCL options + rcl_init_options_t options = rcl_get_zero_initialized_init_options(); + rcl_init_options_init(&options, rcl_get_default_allocator()); + + // Init RCL context + rcl_context_t context = rcl_get_zero_initialized_context(); + rcl_init(0, NULL, &options, &context); + + // Create a node + rcl_node_options_t node_ops = rcl_node_get_default_options(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_init(&node, "pingpong_node", "", &context, &node_ops); + + // Create a reliable ping publisher + rcl_publisher_options_t ping_publisher_ops = rcl_publisher_get_default_options(); + rcl_publisher_t ping_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&ping_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_publisher_ops); + + // Create a best effort pong publisher + rcl_publisher_options_t pong_publisher_ops = rcl_publisher_get_default_options(); + pong_publisher_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_publisher_t pong_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&pong_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_publisher_ops); + + // Create a best effort pong subscriber + rcl_subscription_options_t pong_subscription_ops = rcl_subscription_get_default_options(); + pong_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t pong_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&pong_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_subscription_ops); + + // Create a best effort ping subscriber + rcl_subscription_options_t ping_subscription_ops = rcl_subscription_get_default_options(); + ping_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t ping_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&ping_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_subscription_ops); + + // Create guard condition + rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); + rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options(); + rcl_guard_condition_init(&guard_condition, &context, guard_condition_options); + + pthread_t guard_condition_thread; + pthread_create(&guard_condition_thread, NULL, trigger_guard_condition, &guard_condition); + + // Create a wait set + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_wait_set_init(&wait_set, 2, 1, 0, 0, 0, 0, &context, rcl_get_default_allocator()); + + // Create and allocate the pingpong publication message + std_msgs__msg__Header msg; + char msg_buffer[STRING_BUFFER_LEN]; + msg.frame_id.data = msg_buffer; + msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Create and allocate the pingpong subscription message + std_msgs__msg__Header rcv_msg; + char rcv_buffer[STRING_BUFFER_LEN]; + rcv_msg.frame_id.data = rcv_buffer; + rcv_msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Set device id and sequence number; + int device_id = rand(); + int seq_no; + + int pong_count = 0; + struct timespec ts; + rcl_ret_t rc; + + do { + // Clear and set the waitset + rcl_wait_set_clear(&wait_set); + + size_t index_pong_subscription; + rcl_wait_set_add_subscription(&wait_set, &pong_subscription, &index_pong_subscription); + + size_t index_ping_subscription; + rcl_wait_set_add_subscription(&wait_set, &ping_subscription, &index_ping_subscription); + + size_t index_guardcondition; + rcl_wait_set_add_guard_condition(&wait_set, &guard_condition, &index_guardcondition); + + // Run session for 100 ms + rcl_wait(&wait_set, RCL_MS_TO_NS(100)); + + // Check if some pong message is received + if (wait_set.subscriptions[index_pong_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_pong_subscription], &rcv_msg, NULL, NULL); + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) == 0) { + pong_count++; + printf("Pong for seq %s (%d)\n", rcv_msg.frame_id.data, pong_count); + } + } + + // Check if some ping message is received and pong it + if (wait_set.subscriptions[index_ping_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_ping_subscription], &rcv_msg, NULL, NULL); + + // Dont pong my own pings + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) != 0){ + printf("Ping received with seq %s. Answering.\n", rcv_msg.frame_id.data); + rcl_publish(&pong_publisher, (const void*)&rcv_msg, NULL); + } + } + + // Check if it is time to send a ping + if (wait_set.guard_conditions[index_guardcondition]) { + // Generate a new random sequence number + seq_no = rand(); + sprintf(msg.frame_id.data, "%d_%d", seq_no, device_id); + msg.frame_id.size = strlen(msg.frame_id.data); + + // Fill the message timestamp + clock_gettime(CLOCK_REALTIME, &ts); + msg.stamp.sec = ts.tv_sec; + msg.stamp.nanosec = ts.tv_nsec; + + // Reset the pong count and publish the ping message + pong_count = 0; + rcl_publish(&ping_publisher, (const void*)&msg, NULL); + printf("Ping send seq %s\n", msg.frame_id.data); + } + + usleep(10000); + } while (true); +} +``` + +Don't forget to register your app in `src/uros/micro-ROS-demos/rcl/CMakeLists.txt` by adding the following line: + +``` +export_executable(my_brand_new_app) +``` + +## Running the micro-ROS app + +The micro-ROS app is ready to connect to a micro-ROS-Agent and start talking with the rest of the ROS 2 world. + +First of all, create a micro-ROS agent: + +```bash +# Download micro-ROS-Agent packages +ros2 run micro_ros_setup create_agent_ws.sh +``` + +When the all client and agent packages are ready, just build them all: + +```bash +# Build step +ros2 run micro_ros_setup build_firmware.sh +source install/local_setup.bash +``` + +Then run the agent: + +```bash +# Run a micro-ROS agent +ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888 +``` + +Then run the app in another command line (remember sourcing ROS 2 and micro-ROS installation): + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash +source install/local_setup.bash + +# Run a micro-ROS agent +ros2 run micro_ros_demos_rcl my_brand_new_app +``` + +And finally, let's check that everything is working in another command line. We are going to listen to ping topic to check whether the Ping Pong node is publishing its own pings: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS ping topic +ros2 topic echo /microROS/ping +``` + +You should see the topic messages published by the Ping Pong node every 5 seconds: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 20 + nanosec: 867000000 +frame_id: '1344887256_1085377743' +--- +stamp: + sec: 25 + nanosec: 942000000 +frame_id: '730417256_1085377743' +--- +``` + +On another command line, let's subscribe to the pong topic + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS pong topic +ros2 topic echo /microROS/pong +``` + +At this point, we know that our app is publishing pings. Let's check if it also answers to someone else pings in a new command line: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Send a fake ping +ros2 topic pub --once /microROS/ping std_msgs/msg/Header '{frame_id: "fake_ping"}' +``` + +Now, we should see on the ping subscriber our fake ping along with the board pings: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +stamp: + sec: 305 + nanosec: 973000000 +frame_id: '451230256_1085377743' +--- +stamp: + sec: 310 + nanosec: 957000000 +frame_id: '2084670932_1085377743' +--- +``` + +And in the pong subscriber, we should see the board's answer to our fake ping: + +``` +user@user:~$ ros2 topic echo /microROS/pong +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +``` + + +## Multiple Ping Pong nodes + +One of the advantages of having an Linux micro-ROS app is that you don't need to buy a bunch of hardware in order to test some multi-node micro-ROS apps. So, with the same micro-ROS agent of the last section, let's open four different command lines and run the following on each: + +```bash +cd microros_ws + +source /opt/ros/$ROS_DISTRO/setup.bash +source install/local_setup.bash + +ros2 run micro_ros_demos_rcl my_brand_new_app +``` + +As soon as all micro-ROS nodes are up and connected to the micro-ROS agent you will see them interacting: + +``` +user@user$ ros2 run micro_ros_demos_rcl my_brand_new_app +UDP mode => ip: 127.0.0.1 - port: 8888 +Ping send seq 1711620172_1742614911 <---- This micro-ROS node sends a ping with ping ID "1711620172" and node ID "1742614911" +Pong for seq 1711620172_1742614911 (1) <---- The first mate pongs my ping +Pong for seq 1711620172_1742614911 (2) <---- The second mate pongs my ping +Pong for seq 1711620172_1742614911 (3) <---- The third mate pongs my ping +Ping received with seq 1845948271_546591567. Answering. <---- A ping is received from a mate identified as "546591567", let's pong it. +Ping received with seq 232977719_1681483056. Answering. <---- A ping is received from a mate identified as "1681483056", let's pong it. +Ping received with seq 1134264528_1107823050. Answering. <---- A ping is received from a mate identified as "1107823050", let's pong it. +Ping send seq 324239260_1742614911 +Pong for seq 324239260_1742614911 (1) +Pong for seq 324239260_1742614911 (2) +Pong for seq 324239260_1742614911 (3) +Ping received with seq 1435780593_546591567. Answering. +Ping received with seq 2034268578_1681483056. Answering. +``` diff --git a/_docs/tutorials/advanced/tracing/index.md b/_docs/tutorials/advanced/linux/tracing/index.md similarity index 98% rename from _docs/tutorials/advanced/tracing/index.md rename to _docs/tutorials/advanced/linux/tracing/index.md index 235e3479..7555922d 100644 --- a/_docs/tutorials/advanced/tracing/index.md +++ b/_docs/tutorials/advanced/linux/tracing/index.md @@ -1,8 +1,10 @@ --- title: Getting started with ROS 2 tracing author: christophebedard -permalink: /docs/tutorials/advanced/nuttx/tracing/ -redirect_from: /tracing/ +permalink: /docs/tutorials/advanced/linux/tracing/ +redirect_from: + - /docs/tutorials/advanced/tracing/ + - /tracing/ --- - [Introduction](#introduction) diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/1.jpg b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/1.jpg new file mode 100644 index 00000000..a1329cda Binary files /dev/null and b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/1.jpg differ diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/2.jpg b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/2.jpg new file mode 100644 index 00000000..962d5666 Binary files /dev/null and b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/2.jpg differ diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/5.jpg b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/5.jpg new file mode 100644 index 00000000..f74ee208 Binary files /dev/null and b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/5.jpg differ diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_examples.png b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_examples.png new file mode 100644 index 00000000..8d442232 Binary files /dev/null and b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_examples.png differ diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_menuconfig.png b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_menuconfig.png new file mode 100644 index 00000000..e9362c0c Binary files /dev/null and b/_docs/tutorials/advanced/nuttx/add_a_microros_application/images/nuttx_menuconfig.png differ diff --git a/_docs/tutorials/advanced/nuttx/add_a_microros_application/index.md b/_docs/tutorials/advanced/nuttx/add_a_microros_application/index.md new file mode 100644 index 00000000..ee1c2539 --- /dev/null +++ b/_docs/tutorials/advanced/nuttx/add_a_microros_application/index.md @@ -0,0 +1,465 @@ +--- +title: Add a new Micro-ROS application +permalink: /docs/tutorials/advanced/nuttx/add_a_microros_application/ +--- + +| RTOS | Board Compatible | ROS2 Version | +|:-----:|-------------------|:------------:| +| NuttX | Olimex-STM32-E407 | Dashing | + +In this tutorial, we will follow a guide of how to **add a new Micro-ROS application** on the NuttX RTOS. During this guide, we will start with how to create a configuration profile for our application, following of how to create a micro-ROS pingpong application and finalizing of how we can add our new application to NuttX. + +## Build the Micro-ROS build system + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +mkdir uros_ws && cd uros_ws + +git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build + +sudo apt update && rosdep update +rosdep install --from-path src --ignore-src -y + +colcon build + +source install/local_setup.bash +``` +## Create micro-ROS firmware + +This step will download all the required software. +```bash +ros2 run micro_ros_setup create_firmware_ws.sh nuttx olimex-stm32-e407 +``` +At this point we have everything ready in our workspace to develop a new application. With the next steps, we will start the development of the app itself. + +## Aplication development + +- Go to: ``uros_ws/firmware/apps/examples`` +- Create a folder called ``uros_pingpong`` + +Now we're going to considerer the folder application the next folder: ``uros_ws/firmware/apps/examples/uros_ws/firmware/apps/examples`` + +### Create Kconfig file + +For this step, you need to create an empty file called **Kconfig**, inside the application folder. These files contain the configuration menu to configure the application and add it to the build system list of NuttX. + +In the next lines you can see an example of a basic generic implementation: +```bash +config UROS_PINGPONG_EXAMPLE + bool "micro-ROS Ping Pong" + default n + depends on UROS + ---help--- + + +if UROS_PINGPONG_EXAMPLE + +config UROS_PINGPONG_EXAMPLE_PROGNAME + string "Program name" + default "uros_ping_pong" + depends on BUILD_KERNEL + ---help--- + This is the name of the program that will be use when the NSH ELF + program is installed. + +endif +``` + +### Create Makefile + +Create an empty file called **Makefile**, inside of the application folder. +Below, you can see an example of a generic implementation: +```Makefile +-include $(TOPDIR)/Make.defs + +#Set the scheduler priority for the app. +CONFIG_UROS_PINGPONG_EXAMPLE_PRIORITY ?= SCHED_PRIORITY_DEFAULT +#Set the stack size to the app. The minimum stack size on NuttX for a micro-ROS App is 65000 bytes +CONFIG_UROS_PINGPONG_EXAMPLE_STACKSIZE ?= 65000 + +#This is the name of the app on the NSH console +APPNAME = uros_pingpong +PRIORITY = $(CONFIG_UROS_PINGPONG_EXAMPLE_PRIORITY) +STACKSIZE = $(CONFIG_UROS_PINGPONG_EXAMPLE_STACKSIZE) + +#Add the source files. +ASRCS = +CSRCS = +MAINSRC = uros_pingpong_main.c + +CONFIG_UROS_PINGPONG_EXAMPLE_PROGNAME ?= uros_pingpong$(EXEEXT) +PROGNAME = $(CONFIG_UROS_PINGPONG_EXAMPLE_PROGNAME) +UROS_PINGPONG_INCLUDES = $(shell find $(APPDIR)/$(CONFIG_UROS_DIR)/install -type d -name include) +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(UROS_PINGPONG_INCLUDES)"} -std=c99 + +MODULE = CONFIG_UROS_PINGPONG_EXAMPLE + +include $(APPDIR)/Application.mk +``` + +### Create Make.defs file +Create an empty file called **Make.defs**, inside of the application folder. +You need to add the following lines: +```Makefile +ifeq ($(CONFIG_UROS_PINGPONG_EXAMPLE),y) + CONFIGURED_APPS += examples/uros_pingpong +endif +``` + +This file will add the folder as an application if you set the option on the configuration menu of NuttX. + +### Create the main file + +Create a file named ``uros_pingpong_main.c``. +In the box below, we will show a pinpong example: +```c +//Nuttx specific library +#include + +// Micro-ROS specific library +#include +#include +#include "rosidl_generator_c/string_functions.h" +#include +#include + +// C standard library +#include +#include +#include +#include + +#define STRING_BUFFER_LEN 100 + +// Thread to trigger a publication guard condition +void * trigger_guard_condition(void *args){ + rcl_guard_condition_t * guard_condition = (rcl_guard_condition_t *)args; + + while(true){ + rcl_trigger_guard_condition(guard_condition); + sleep(5); + } +} + +#if defined(BUILD_MODULE) +int main(int argc, char *argv[]) +#else +int uros_pingpong_main(int argc, char* argv[]) +#endif +{ + //Init RCL options + rcl_init_options_t options = rcl_get_zero_initialized_init_options(); + rcl_init_options_init(&options, rcl_get_default_allocator()); + + // Init RCL context + rcl_context_t context = rcl_get_zero_initialized_context(); + rcl_init(0, NULL, &options, &context); + + // Create a node + rcl_node_options_t node_ops = rcl_node_get_default_options(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_init(&node, "pingpong_node", "", &context, &node_ops); + + // Create a reliable ping publisher + rcl_publisher_options_t ping_publisher_ops = rcl_publisher_get_default_options(); + rcl_publisher_t ping_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&ping_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_publisher_ops); + + // Create a best effort pong publisher + rcl_publisher_options_t pong_publisher_ops = rcl_publisher_get_default_options(); + pong_publisher_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_publisher_t pong_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&pong_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_publisher_ops); + + // Create a reliable pong subscriber + rcl_subscription_options_t pong_subscription_ops = rcl_subscription_get_default_options(); + rcl_subscription_t pong_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&pong_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_subscription_ops); + + // Create a best effort ping subscriber + rcl_subscription_options_t ping_subscription_ops = rcl_subscription_get_default_options(); + ping_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t ping_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&ping_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_subscription_ops); + + // Create a guard condition + rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); + rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options(); + rcl_guard_condition_init(&guard_condition, &context, guard_condition_options); + + // Create a thread that triggers the guard condition + pthread_t guard_condition_thread; + pthread_create(&guard_condition_thread, NULL, trigger_guard_condition, &guard_condition); + + // Create a wait set + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_wait_set_init(&wait_set, 2, 1, 0, 0, 0, 0, &context, rcl_get_default_allocator()); + + // Create and allocate the pingpong publication message + std_msgs__msg__Header msg; + char msg_buffer[STRING_BUFFER_LEN]; + msg.frame_id.data = msg_buffer; + msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Create and allocate the pingpong subscription message + std_msgs__msg__Header rcv_msg; + char rcv_buffer[STRING_BUFFER_LEN]; + rcv_msg.frame_id.data = rcv_buffer; + rcv_msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Set device id and sequence number; + int device_id = rand(); + int seq_no; + + int pong_count = 0; + struct timespec ts; + rcl_ret_t rc; + + do { + // Clear and set the waitset + rcl_wait_set_clear(&wait_set); + + size_t index_pong_subscription; + rcl_wait_set_add_subscription(&wait_set, &pong_subscription, &index_pong_subscription); + + size_t index_ping_subscription; + rcl_wait_set_add_subscription(&wait_set, &ping_subscription, &index_ping_subscription); + + size_t index_guardcondition; + rcl_wait_set_add_guard_condition(&wait_set, &guard_condition, &index_guardcondition); + + // Run session for 100 ms + rcl_wait(&wait_set, RCL_MS_TO_NS(100)); + + // Check if it is time to send a ping + if (wait_set.guard_conditions[index_guardcondition]) { + // Generate a new random sequence number + seq_no = rand(); + sprintf(msg.frame_id.data, "%d_%d", seq_no, device_id); + msg.frame_id.size = strlen(msg.frame_id.data); + + // Fill the message timestamp + clock_gettime(CLOCK_REALTIME, &ts); + msg.stamp.sec = ts.tv_sec; + msg.stamp.nanosec = ts.tv_nsec; + + // Reset the pong count and publish the ping message + pong_count = 0; + rcl_publish(&ping_publisher, (const void*)&msg, NULL); + // printf("Ping send seq 0x%x\n", seq_no); + } + + // Check if some pong message is received + if (wait_set.subscriptions[index_pong_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_pong_subscription], &rcv_msg, NULL, NULL); + + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) == 0) { + pong_count++; + // printf("Pong for seq 0x%x (%d)\n", seq_no, pong_count); + } + } + + // Check if some ping message is received and pong it + if (wait_set.subscriptions[index_ping_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_ping_subscription], &rcv_msg, NULL, NULL); + + // Dont pong my own pings + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) != 0){ + // printf("Ping received with seq 0x%x (%d). Answering.\n", seq_no); + rcl_publish(&pong_publisher, (const void*)&rcv_msg, NULL); + } + } + + usleep(10000); + } while (true); +} +``` + +Once the application is ready, the only thing left to do is to create the right configuration. + +## Create a config profile + +Create a specific configuration from scratch can be a challenging task, so we're going to start from an already existing one and modify it for our new application. + +Execute the next command: +```bash +cd ~/uros_ws +ros2 run micro_ros_setup configure_firmware.sh uros +``` + +This sets the Ethernet and Micro-ROS required configuration. However, in order to add our application, we're going to modify it. + +### Modify the configuration +Now type the following commands: +```bash +cd uros_ws/firmware/NuttX +make menuconfig +``` + +This will open the NuttX menu config, which allows you to modify the configuration of the RTOS, including adding a new application. + + +- On the menu, you need to follow the next path: +``Application Configuration -> Examples `` +![](images/nuttx_menuconfig.png) + +- This will show a list of the available applications. You need to find: ``micro-ROS Ping-Pong`` and click ``y`` to add it. +![](images/nuttx_examples.png) + +- Now push three times the key ``ESC`` to close the menu. You will be asked if you want to save the save your new configuration, and you need to click ``Yes``. + + +### Add your configuration + +Execute the following commands: +```bash +cd uros_ws/firmware/NuttX +make savedefconfig +``` + +This will generate a file called ``defconfig`` inside of ``uros_ws/firmware/NuttX``. This file is a config profile with all the required configuration to run your specific configuration which includes your application. + +Finally create a folder called ``uros_pingpong`` into ``uros_ws/firmware/NuttX/configs/olimex-stm32-e407`` and move the defconfig file to uros_pingpong folder. + +## Build your application + +Now that everything is ready, the only thing left to do is to continue with the build system instructions. Execute the next command on the build system to start the build process: +```bash +cd ~/uros_ws +ros2 run micro_ros_setup configure_firmware.sh uros_pingpong +ros2 run micro_ros_setup build_firmware.sh +``` + +If it returns the next output, your build step succeded and your application was implemented properly. + +```bash +AR: stm32_boot.o stm32_bringup.o stm32_spi.o libatomic.o stm32_autoleds.o stm32_buttons.o stm32_appinit.o stm32_usb.o +make[2]: Leaving directory '/home/juan/uros_pinpong/firmware/NuttX/configs/olimex-stm32-e407/src' +LD: nuttx +arm-none-eabi-ld --entry=__start -nostartfiles -nodefaultlibs -g -T/home/juan/uros_pinpong/firmware/NuttX/configs/olimex-stm32-e407/scripts/ld.script -L"/home/juan/uros_pinpong/firmware/NuttX/staging" -L"/home/juan/uros_pinpong/firmware/NuttX/arch/arm/src/board" -L "/usr/lib/gcc/arm-none-eabi/6.3.1/../../../arm-none-eabi/lib/thumb/v7e-m" \ + -o "/home/juan/uros_pinpong/firmware/NuttX/nuttx" \ + --start-group -lsched -ldrivers -lconfigs -lc -lmm -larch -lxx -lapps -lnet -lfs -lbinfmt -lxx -lboard -lsupc++ "/usr/lib/gcc/arm-none-eabi/6.3.1/thumb/v7e-m/libgcc.a" --end-group +make[1]: Leaving directory '/home/juan/uros_pinpong/firmware/NuttX/arch/arm/src' +CP: nuttx.hex +CP: nuttx.bin + +``` +Now the firmware is ready, is just necessary to flash the board. First, connect Olimex ARM-USB-TINY-H JTAG programmer to the board's JTAG port: + + + +Make sure that the board power supply jumper (PWR_SEL) is in the 3-4 position in order to power the board from the JTAG connector: + + + +You should see the red LED lighting. It is time to flash the board: + +```bash +# Flash step +ros2 run micro_ros_setup flash_firmware.sh +``` +## Running the micro-ROS app + +The micro-ROS app is ready to connect to a micro-ROS-Agent and start talking with the rest of the ROS 2 world. + +First of all, create and build a micro-ROS agent: + +```bash +# Download micro-ROS-Agent packages +ros2 run micro_ros_setup create_agent_ws.sh + +# Build micro-ROS-Agent packages, this may take a while. +colcon build --metas src +source install/local_setup.bash +``` + +Then connect the Olimex development board to the computer using the usb to serial cable: + + + +***TIP:** Color codes are applicable to [this cable](https://www.olimex.com/Products/Components/Cables/USB-Serial-Cable/USB-Serial-Cable-F/). Make sure to match Olimex Rx with Cable Tx and vice-versa. Remember GND!* + +Then run the agent: + +```bash +# Run a micro-ROS agent +ros2 run micro_ros_agent micro_ros_agent serial --dev [device] +``` + +***TIP:** you can use this command to find your serial device name: `ls /dev/serial/by-id/*`* + +And finally, let's check that everything is working in a new command line. We are going to listen to ping topic to check whether the Ping Pong node is publishing its own pings + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS ping topic +ros2 topic echo /microROS/ping +``` + +You should see the topic messages published by the Ping Pong node every 5 seconds: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 20 + nanosec: 867000000 +frame_id: '1344887256_1085377743' +--- +stamp: + sec: 25 + nanosec: 942000000 +frame_id: '730417256_1085377743' +--- +``` + +On another command line, let's subscribe to the pong topic + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS pong topic +ros2 topic echo /microROS/pong +``` + +At this point, we know that our app is publishing pings. Let's check if it also answers to someone else pings in a new command line: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Send a fake ping +ros2 topic pub --once /microROS/ping std_msgs/msg/Header '{frame_id: "fake_ping"}' +``` + +Now, we should see on the ping subscriber our fake ping along with the board pings: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +stamp: + sec: 305 + nanosec: 973000000 +frame_id: '451230256_1085377743' +--- +stamp: + sec: 310 + nanosec: 957000000 +frame_id: '2084670932_1085377743' +--- +``` + +And in the pong subscriber, we should see the board's answer to our fake ping: + +``` +user@user:~$ ros2 topic echo /microROS/pong +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +``` \ No newline at end of file diff --git a/_docs/tutorials/advanced/zephyr/zephyr_emulator/imgs/4.jpg b/_docs/tutorials/advanced/zephyr/zephyr_emulator/imgs/4.jpg new file mode 100644 index 00000000..6f3ad643 Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_emulator/imgs/4.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_emulator/index.md b/_docs/tutorials/advanced/zephyr/zephyr_emulator/index.md new file mode 100644 index 00000000..c9d6cb6f --- /dev/null +++ b/_docs/tutorials/advanced/zephyr/zephyr_emulator/index.md @@ -0,0 +1,404 @@ +--- +title: Zephyr Emulator +permalink: /docs/tutorials/advanced/zephyr/zephyr_emulator/ +--- + +This tutorial aims to create a new micro-ROS application on with **[Zephyr RTOS](https://www.zephyrproject.org/)** emulator (also known as [Native POSIX](https://docs.zephyrproject.org/latest/boards/posix/native_posix/doc/index.html)). + +
+ +
+ +## Required hardware + +This tutorial requires no hardware beyond a Linux host computer. + +## Adding a new micro-ROS app + +First of all, make sure that you have a **ROS 2** installation. + +***TIP:** if you are familiar with Docker containers, this image may be useful: [ros:dashing](https://hub.docker.com/layers/ros/library/ros/dashing/images/sha256-b796c14ea663537129897769aa6c715a851ca08dffd4875ef2ecaa31a4dbd431?context=explore)* + +On the **ROS 2** installation open a command line and follow these steps: + +```bash +# Source the ROS 2 installation +source /opt/ros/$ROS_DISTRO/setup.bash + +# Create a workspace and download the micro-ROS tools +mkdir microros_ws +cd microros_ws +git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build + +# Update dependencies using rosdep +sudo apt update && sydo apt install python3-colcon-metadata +rosdep update +rosdep install --from-path src --ignore-src -y + +# Build micro-ROS tools and source them +colcon build +source install/local_setup.bash +``` + +Let's install the last version of CMake: + +```bash +sudo apt install wget +wget -O - https://apt.kitware.com/keys/kitware-archive-latest.asc 2>/dev/null | sudo apt-key add - +sudo apt install software-properties-common +sudo apt-add-repository 'deb https://apt.kitware.com/ubuntu/ bionic main' +sudo apt update +sudo apt install cmake +``` + +Now, let's create a firmware workspace that targets all the required code and tools for Zephyr emulator: + +```bash +# Create firmware step +ros2 run micro_ros_setup create_firmware_ws.sh zephyr host +``` + +Now you have all the required tools to compile micro-ROS and Zephyr. At this point, you must know that the micro-ROS build system is a four-step workflow: + + +1. **Create**: retrieves all the required packages for a specific RTOS and hardware platform. +2. **Configure**: configures the downloaded packages with options such as the micro-ROS application, the selected transport layer or the micro-ROS agent IP address (in network transports). +3. **Build**: generates a binary file ready for being loaded in the hardware. +4. **Flash**: load the micro-ROS software in the hardware. + +micro-ROS apps for Zephyr emulator are located at `firmware/zephyr_apps/apps`. In order to create a new application, create a new folder containing two files: the app code (inside a `src` folder) and the RMW configuration. You will also need some other Zephyr related files: a `CMakeLists.txt` to define the building process and a `prj.conf` where Zephyr is configured. You have these two files [here](https://github.com/micro-ROS/zephyr_apps/tree/dashing/apps/host_ping_pong), for now, it is ok to copy them. + +```bash +# Creating a new app +pushd firmware/zephyr_apps/apps +mkdir my_brand_new_app +cd my_brand_new_app +mkdir src +touch src/app.c app-colcon.meta + +# Copying CMakeLists.txt and prj.conf +wget https://raw.githubusercontent.com/micro-ROS/zephyr_apps/dashing/apps/host_ping_pong/CMakeLists.txt +wget https://raw.githubusercontent.com/micro-ROS/zephyr_apps/dashing/apps/host_ping_pong/prj.conf + +popd +``` + +For this example we are going to create a ping pong app where a node sends a ping package with a unique identifier using a publisher and the same package is received by a pong subscriber. The node will also answer to pings received from other nodes with a pong message: + +![pingpong](http://www.plantuml.com/plantuml/png/ZOwnIWGn48RxFCNFzSkoUG2vqce5jHEHi1dtWZkPa6GByNntavZY10yknMJu-ORlFwPiOjvvK-d3-M2YOR1uMKvHc93ZJafvoMML07d7h1NAE-DPWblg_na8vnwEx9OeZmzFOt1-BK7AzetJciPxCfRYVw1S0SbRLBEg1IpXPIvpUWLCmZpXIm6BS3addt7uQpu0ZQlxT1MK2r0g-7sfqbsbRrVfMrMwgbev3CDTlsqJGtJhATUmSMrMg5TKwaZUxfcttuMt7m00) + +To start creating this app, lets configure the RMW with the required static memory. You can read more about RMW and Micro XRCE-DDS Configuration [here](/docs/tutorials/core/microxrcedds_rmw_configuration/). The `app-colcon.meta` should look like: + +``` +{ + "names": { + "rmw_microxrcedds": { + "cmake-args": [ + "-DRMW_UXRCE_MAX_NODES=1", + "-DRMW_UXRCE_MAX_PUBLISHERS=2", + "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=2", + "-DRMW_UXRCE_MAX_SERVICES=0", + "-DRMW_UXRCE_MAX_CLIENTS=0", + "-DRMW_UXRCE_MAX_HISTORY=4", + ] + } + } +} +``` + +Meanwhile `src/app.c` should look like the following code: + +```c +#include +#include +#include +#include "rosidl_generator_c/string_functions.h" +#include + +#include + +#include +#include +#include + +#include + +#define STRING_BUFFER_LEN 100 + +// App main function +void main(void) +{ + //Init RCL options + rcl_init_options_t options = rcl_get_zero_initialized_init_options(); + rcl_init_options_init(&options, rcl_get_default_allocator()); + + // Init RCL context + rcl_context_t context = rcl_get_zero_initialized_context(); + rcl_init(0, NULL, &options, &context); + + // Create a node + rcl_node_options_t node_ops = rcl_node_get_default_options(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_init(&node, "pingpong_node", "", &context, &node_ops); + + // Create a reliable ping publisher + rcl_publisher_options_t ping_publisher_ops = rcl_publisher_get_default_options(); + rcl_publisher_t ping_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&ping_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_publisher_ops); + + // Create a best effort pong publisher + rcl_publisher_options_t pong_publisher_ops = rcl_publisher_get_default_options(); + pong_publisher_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_publisher_t pong_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&pong_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_publisher_ops); + + // Create a best effort pong subscriber + rcl_subscription_options_t pong_subscription_ops = rcl_subscription_get_default_options(); + pong_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t pong_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&pong_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_subscription_ops); + + // Create a best effort ping subscriber + rcl_subscription_options_t ping_subscription_ops = rcl_subscription_get_default_options(); + ping_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t ping_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&ping_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_subscription_ops); + + // Create a wait set + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_wait_set_init(&wait_set, 2, 0, 0, 0, 0, 0, &context, rcl_get_default_allocator()); + + // Create and allocate the pingpong publication message + std_msgs__msg__Header msg; + char msg_buffer[STRING_BUFFER_LEN]; + msg.frame_id.data = msg_buffer; + msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Create and allocate the pingpong subscription message + std_msgs__msg__Header rcv_msg; + char rcv_buffer[STRING_BUFFER_LEN]; + rcv_msg.frame_id.data = rcv_buffer; + rcv_msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Set device id and sequence number; + int device_id = rand(); + int seq_no; + + int pong_count = 0; + struct timespec ts; + rcl_ret_t rc; + + uint32_t iterations = 0; + + do { + // Clear and set the waitset + rcl_wait_set_clear(&wait_set); + + size_t index_pong_subscription; + rcl_wait_set_add_subscription(&wait_set, &pong_subscription, &index_pong_subscription); + + size_t index_ping_subscription; + rcl_wait_set_add_subscription(&wait_set, &ping_subscription, &index_ping_subscription); + + // Run session for 100 ms + rcl_wait(&wait_set, RCL_MS_TO_NS(100)); + + // Check if some pong message is received + if (wait_set.subscriptions[index_pong_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_pong_subscription], &rcv_msg, NULL, NULL); + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) == 0) { + pong_count++; + printf("Pong for seq %s (%d)\n", rcv_msg.frame_id.data, pong_count); + } + } + + // Check if some ping message is received and pong it + if (wait_set.subscriptions[index_ping_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_ping_subscription], &rcv_msg, NULL, NULL); + + // Dont pong my own pings + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) != 0){ + printf("Ping received with seq %s. Answering.\n", rcv_msg.frame_id.data); + rcl_publish(&pong_publisher, (const void*)&rcv_msg, NULL); + } + } + + // Check if it is time to send a ping + if (iterations++ % 50 == 0) { + // Generate a new random sequence number + seq_no = rand(); + sprintf(msg.frame_id.data, "%d_%d", seq_no, device_id); + msg.frame_id.size = strlen(msg.frame_id.data); + + // Fill the message timestamp + clock_gettime(CLOCK_REALTIME, &ts); + msg.stamp.sec = ts.tv_sec; + msg.stamp.nanosec = ts.tv_nsec; + + // Reset the pong count and publish the ping message + pong_count = 0; + rcl_publish(&ping_publisher, (const void*)&msg, NULL); + printf("Ping send seq %s\n", msg.frame_id.data); + } + + usleep(10000); + } while (true); +} +``` + +Once the new folder is created, let's configure our new app with a UDP transport that looks for the agent on the port UDP/8888 at localhost: + +```bash +# Configure step +ros2 run micro_ros_setup configure_firmware.sh my_brand_new_app --transport udp --ip 127.0.0.1 --port 8888 +``` + +When the configuring step ends, just build the firmware: + +```bash +# Build step +ros2 run micro_ros_setup build_firmware.sh +``` + +Now you have a Zephyr + micro-ROS app ready to run on your own computer. + +## Running the micro-ROS app + +The micro-ROS app is ready to connect to a micro-ROS-Agent and start talking with the rest of the ROS 2 world. + +First of all, create and build a micro-ROS agent: + +```bash +# Download micro-ROS-Agent packages +ros2 run micro_ros_setup create_agent_ws.sh + +# Build micro-ROS-Agent packages, this may take a while. +colcon build +source install/local_setup.bash +``` + +Then run the agent: + +```bash +# Run a micro-ROS agent +ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888 +``` + +And run the Zephyr app in another command line (remember sourcing ROS 2 and micro-ROS installation): + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash +source microros_ws/install/local_setup.bash + +# Flash/run step +ros2 run micro_ros_setup flash_firmware.sh +``` + +And finally, let's check that everything is working in another command line. We are going to listen to ping topic to check whether the Ping Pong node is publishing its own pings: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS ping topic +ros2 topic echo /microROS/ping +``` + +You should see the topic messages published by the Ping Pong node every 5 seconds: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 20 + nanosec: 867000000 +frame_id: '1344887256_1085377743' +--- +stamp: + sec: 25 + nanosec: 942000000 +frame_id: '730417256_1085377743' +--- +``` + +On another command line, let's subscribe to the pong topic + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS pong topic +ros2 topic echo /microROS/pong +``` + +At this point, we know that our app is publishing pings. Let's check if it also answers to someone else pings in a new command line: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Send a fake ping +ros2 topic pub --once /microROS/ping std_msgs/msg/Header '{frame_id: "fake_ping"}' +``` + +Now, we should see on the ping subscriber our fake ping along with the board pings: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +stamp: + sec: 305 + nanosec: 973000000 +frame_id: '451230256_1085377743' +--- +stamp: + sec: 310 + nanosec: 957000000 +frame_id: '2084670932_1085377743' +--- +``` + +And in the pong subscriber, we should see the board's answer to our fake ping: + +``` +pgarrido@pgarrido:~$ ros2 topic echo /microROS/pong +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +``` + +## Multiple Ping Pong nodes + +One of the advantages of having an emulator is that you don't need to buy a bunch of hardware in order to test some multi-node micro-ROS apps. So, with the same micro-ROS agent of the last section, let's open four different command lines and run the following on each: + +```bash +cd microros_ws + +# This is an alternative way of executing the Zephyr emulator +./firmware/build/zephyr/zephyr.exe +``` + +As soon as all micro-ROS node are up and connected to the micro-ROS agent you will see them interacting: + +``` +pgarrido@pgarrido$ ./firmware/build/zephyr/zephyr.exe +*** Booting Zephyr OS build zephyr-v2.2.0-492-gc73cb85b4ae9 *** +UDP mode => ip: 127.0.0.1 - port: 8888 +Ping send seq 1711620172_1742614911 <---- This micro-ROS node sends a ping with ping ID "1711620172" and node ID "1742614911" +Pong for seq 1711620172_1742614911 (1) <---- The first mate pongs my ping +Pong for seq 1711620172_1742614911 (2) <---- The second mate pongs my ping +Pong for seq 1711620172_1742614911 (3) <---- The third mate pongs my ping +Ping received with seq 1845948271_546591567. Answering. <---- A ping is received from a mate identified as "546591567", let's pong it. +Ping received with seq 232977719_1681483056. Answering. <---- A ping is received from a mate identified as "1681483056", let's pong it. +Ping received with seq 1134264528_1107823050. Answering. <---- A ping is received from a mate identified as "1107823050", let's pong it. +Ping send seq 324239260_1742614911 +Pong for seq 324239260_1742614911 (1) +Pong for seq 324239260_1742614911 (2) +Pong for seq 324239260_1742614911 (3) +Ping received with seq 1435780593_546591567. Answering. +Ping received with seq 2034268578_1681483056. Answering. +``` + +***TIP:** use the help flag to discover some Zephyr emulation features `./firmware/build/zephyr/zephyr.exe -h`* diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/1.jpg b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/1.jpg new file mode 100644 index 00000000..a1329cda Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/1.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/2.jpg b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/2.jpg new file mode 100644 index 00000000..962d5666 Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/2.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/3.jpg b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/3.jpg new file mode 100644 index 00000000..fe1055b1 Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/3.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/4.jpg b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/4.jpg new file mode 100644 index 00000000..6f3ad643 Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/4.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/5.jpg b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/5.jpg new file mode 100644 index 00000000..f74ee208 Binary files /dev/null and b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/imgs/5.jpg differ diff --git a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/index.md b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/index.md index 1f65ce10..0b690353 100644 --- a/_docs/tutorials/advanced/zephyr/zephyr_getting_started/index.md +++ b/_docs/tutorials/advanced/zephyr/zephyr_getting_started/index.md @@ -3,4 +3,372 @@ title: Zephyr Getting Started permalink: /docs/tutorials/advanced/zephyr/zephyr_getting_started/ --- -WIP \ No newline at end of file + +This tutorial aims to create a new micro-ROS application on **[Olimex STM32-E407](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware)** evaluation board with **[Zephyr RTOS](https://www.zephyrproject.org/)** + +
+ + + +
+ +## Required hardware + +This tutorial uses the following hardware: + +| Item | +|---------------| +| [Olimex STM32-E407](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware) | +| [Olimex ARM-USB-TINY-H](https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H/) | +| [USB-Serial Cable Female](https://www.olimex.com/Products/Components/Cables/USB-Serial-Cable/USB-Serial-Cable-F/) | + + +## Adding a new micro-ROS app + +First of all, make sure that you have a **ROS 2** installation. + +***TIP:** if you are familiar with Docker containers, this image may be useful: [ros:dashing](https://hub.docker.com/layers/ros/library/ros/dashing/images/sha256-b796c14ea663537129897769aa6c715a851ca08dffd4875ef2ecaa31a4dbd431?context=explore)* + +On the **ROS 2** installation open a command line and follow these steps: + +```bash +# Source the ROS 2 installation +source /opt/ros/$ROS_DISTRO/setup.bash + +# Create a workspace and download the micro-ROS tools +mkdir microros_ws +cd microros_ws +git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build + +# Update dependencies using rosdep +sudo apt update && rosdep update +rosdep install --from-path src --ignore-src -y + +# Build micro-ROS tools and source them +colcon build +source install/local_setup.bash +``` + + +Now, let's create a firmware workspace that targets all the required code and tools for Olimex development board and Zephyr: + +```bash +# Create step +ros2 run micro_ros_setup create_firmware_ws.sh zephyr olimex-stm32-e407 +``` + +Now you have all the required tools to crosscompile micro-ROS and Zephyr for Olimex STM32-E407 development board. At this point, you must know that the micro-ROS build system is a four-step workflow: + + +1. **Create**: retrieves all the required packages for a specific RTOS and hardware platform. +2. **Configure**: configures the downloaded packages with options such as the micro-ROS application, the selected transport layer or the micro-ROS agent IP address (in network transports). +3. **Build**: generates a binary file ready for being loaded in the hardware. +4. **Flash**: load the micro-ROS software in the hardware. + +micro-ROS apps for Olimex + Zephyr are located at `firmware/zephyr_apps/apps`. In order to create a new application, create a new folder containing two files: the app code (inside a `src` folder) and the RMW configuration. + +```bash +# Creating a new app +pushd firmware/zephyr_apps/apps +mkdir my_brand_new_app +cd my_brand_new_app +mkdir src +touch src/app.c app-colcon.meta +popd +``` + +You will also need some other Zephyr related files: a `CMakeLists.txt` in order to define the building process and a `prj.conf` where Zephyr is configured. You have these two files [here](https://github.com/micro-ROS/zephyr_apps/tree/dashing/apps/ping_pong), for now it is ok to copy them. + +For this example we are going to create a ping pong app where a node sends a ping package with a unique identifier using a publisher and the same package is received by a pong subscriber. The node will also answer to pings received from other nodes with a pong message: + +![pingpong](http://www.plantuml.com/plantuml/png/ZOwnIWGn48RxFCNFzSkoUG2vqce5jHEHi1dtWZkPa6GByNntavZY10yknMJu-ORlFwPiOjvvK-d3-M2YOR1uMKvHc93ZJafvoMML07d7h1NAE-DPWblg_na8vnwEx9OeZmzFOt1-BK7AzetJciPxCfRYVw1S0SbRLBEg1IpXPIvpUWLCmZpXIm6BS3addt7uQpu0ZQlxT1MK2r0g-7sfqbsbRrVfMrMwgbev3CDTlsqJGtJhATUmSMrMg5TKwaZUxfcttuMt7m00) + +To start creating this app, let's configure the RMW with the required static memory. You can read more about RMW and Micro XRCE-DDS Configuration [here](/docs/tutorials/core/microxrcedds_rmw_configuration/). The `app-colcon.meta` should look like: + +``` +{ + "names": { + "rmw_microxrcedds": { + "cmake-args": [ + "-DRMW_UXRCE_MAX_NODES=1", + "-DRMW_UXRCE_MAX_PUBLISHERS=2", + "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=2", + "-DRMW_UXRCE_MAX_SERVICES=0", + "-DRMW_UXRCE_MAX_CLIENTS=0", + "-DRMW_UXRCE_MAX_HISTORY=4", + ] + } + } +} +``` + +Meanwhile `src/app.c` should look like the following code: + +```c +#include +#include +#include +#include "rosidl_generator_c/string_functions.h" +#include + +#include + +#include +#include + +#include + +#define STRING_BUFFER_LEN 100 + +// App main function +void main(void) +{ + //Init RCL options + rcl_init_options_t options = rcl_get_zero_initialized_init_options(); + rcl_init_options_init(&options, rcl_get_default_allocator()); + + // Init RCL context + rcl_context_t context = rcl_get_zero_initialized_context(); + rcl_init(0, NULL, &options, &context); + + // Create a node + rcl_node_options_t node_ops = rcl_node_get_default_options(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_init(&node, "pingpong_node", "", &context, &node_ops); + + // Create a reliable ping publisher + rcl_publisher_options_t ping_publisher_ops = rcl_publisher_get_default_options(); + rcl_publisher_t ping_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&ping_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_publisher_ops); + + // Create a best effort pong publisher + rcl_publisher_options_t pong_publisher_ops = rcl_publisher_get_default_options(); + pong_publisher_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_publisher_t pong_publisher = rcl_get_zero_initialized_publisher(); + rcl_publisher_init(&pong_publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_publisher_ops); + + // Create a best effort pong subscriber + rcl_subscription_options_t pong_subscription_ops = rcl_subscription_get_default_options(); + pong_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t pong_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&pong_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/pong", &pong_subscription_ops); + + // Create a best effort ping subscriber + rcl_subscription_options_t ping_subscription_ops = rcl_subscription_get_default_options(); + ping_subscription_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + rcl_subscription_t ping_subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_init(&ping_subscription, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Header), "/microROS/ping", &ping_subscription_ops); + + // Create a wait set + rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); + rcl_wait_set_init(&wait_set, 2, 0, 0, 0, 0, 0, &context, rcl_get_default_allocator()); + + // Create and allocate the pingpong publication message + std_msgs__msg__Header msg; + char msg_buffer[STRING_BUFFER_LEN]; + msg.frame_id.data = msg_buffer; + msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Create and allocate the pingpong subscription message + std_msgs__msg__Header rcv_msg; + char rcv_buffer[STRING_BUFFER_LEN]; + rcv_msg.frame_id.data = rcv_buffer; + rcv_msg.frame_id.capacity = STRING_BUFFER_LEN; + + // Set device id and sequence number; + int device_id = rand(); + int seq_no; + + int pong_count = 0; + struct timespec ts; + rcl_ret_t rc; + + uint32_t iterations = 0; + + do { + // Clear and set the waitset + rcl_wait_set_clear(&wait_set); + + size_t index_pong_subscription; + rcl_wait_set_add_subscription(&wait_set, &pong_subscription, &index_pong_subscription); + + size_t index_ping_subscription; + rcl_wait_set_add_subscription(&wait_set, &ping_subscription, &index_ping_subscription); + + // Run session for 100 ms + rcl_wait(&wait_set, RCL_MS_TO_NS(100)); + + // Check if it is time to send a ping + if (iterations++ % 50 == 0) { + // Generate a new random sequence number + seq_no = rand(); + sprintf(msg.frame_id.data, "%d_%d", seq_no, device_id); + msg.frame_id.size = strlen(msg.frame_id.data); + + // Fill the message timestamp + clock_gettime(CLOCK_REALTIME, &ts); + msg.stamp.sec = ts.tv_sec; + msg.stamp.nanosec = ts.tv_nsec; + + // Reset the pong count and publish the ping message + pong_count = 0; + rcl_publish(&ping_publisher, (const void*)&msg, NULL); + printf("Ping send seq %s\n", msg.frame_id.data); + } + + // Check if some pong message is received + if (wait_set.subscriptions[index_pong_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_pong_subscription], &rcv_msg, NULL, NULL); + + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) == 0) { + pong_count++; + printf("Pong for seq %s (%d)\n", rcv_msg.frame_id.data, pong_count); + } + } + + // Check if some ping message is received and pong it + if (wait_set.subscriptions[index_ping_subscription]) { + rc = rcl_take(wait_set.subscriptions[index_ping_subscription], &rcv_msg, NULL, NULL); + + // Dont pong my own pings + if(rc == RCL_RET_OK && strcmp(msg.frame_id.data,rcv_msg.frame_id.data) != 0){ + printf("Ping received with seq %s. Answering.\n", rcv_msg.frame_id.data); + rcl_publish(&pong_publisher, (const void*)&rcv_msg, NULL); + } + } + + usleep(10000); + } while (true); +} +``` + +Once the new folder is created, let's configure our new app with a serial transport on the USB: + +```bash +# Configure step +ros2 run micro_ros_setup configure_firmware.sh my_brand_new_app --transport serial-usb +``` + +When the configuring step ends, just build the firmware: + +```bash +# Build step +ros2 run micro_ros_setup build_firmware.sh +``` + +Once the build has successfully ended, let's power and connect the board. First, connect Olimex ARM-USB-TINY-H JTAG programmer to the board's JTAG port: + + + +Make sure that the board power supply jumper (PWR_SEL) is in the 3-4 position in order to power the board from the JTAG connector: + + + +You should see the red LED lighting. It is time to flash the board: + +```bash +# Flash step +ros2 run micro_ros_setup flash_firmware.sh +``` +## Running the micro-ROS app + +The micro-ROS app is ready to connect to a micro-ROS-Agent and start talking with the rest of the ROS 2 world. + +First of all, create and build a micro-ROS agent: + +```bash +# Download micro-ROS-Agent packages +ros2 run micro_ros_setup create_agent_ws.sh + +# Build micro-ROS-Agent packages, this may take a while. +colcon build +source install/local_setup.bash +``` + +Then connect the Olimex development board to the computer using the USB OTG 2 connector (the miniUSB connector that is furthest from the Ethernet port). + +***TIP:** Color codes are applicable to [this cable](https://www.olimex.com/Products/Components/Cables/USB-Serial-Cable/USB-Serial-Cable-F/). Make sure to match Olimex Rx with Cable Tx and vice-versa. Remember GND!* + +Then run the agent: + +```bash +# Run a micro-ROS agent +ros2 run micro_ros_agent micro_ros_agent serial --dev [device] +``` + +***TIP:** you can use this command to find your serial device name: `ls /dev/serial/by-id/*`. Probably it will be something like `/dev/serial/by-id/usb-ZEPHYR_Zephyr_microROS_3536510100290035-if00`* + +And finally, let's check that everything is working in another command line. We are going to listen to ping topic to check whether the Ping Pong node is publishing its own pings + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS ping topic +ros2 topic echo /microROS/ping +``` + +You should see the topic messages published by the Ping Pong node every 5 seconds: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 20 + nanosec: 867000000 +frame_id: '1344887256_1085377743' +--- +stamp: + sec: 25 + nanosec: 942000000 +frame_id: '730417256_1085377743' +--- +``` + +On another command line, let's subscribe to the pong topic + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Subscribe to micro-ROS pong topic +ros2 topic echo /microROS/pong +``` + +At this point, we know that our app is publishing pings. Let's check if it also answers to someone else pings in a new command line: + +```bash +source /opt/ros/$ROS_DISTRO/setup.bash + +# Send a fake ping +ros2 topic pub --once /microROS/ping std_msgs/msg/Header '{frame_id: "fake_ping"}' +``` + +Now, we should see on the ping subscriber our fake ping along with the board pings: + +``` +user@user:~$ ros2 topic echo /microROS/ping +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +stamp: + sec: 305 + nanosec: 973000000 +frame_id: '451230256_1085377743' +--- +stamp: + sec: 310 + nanosec: 957000000 +frame_id: '2084670932_1085377743' +--- +``` + +And in the pong subscriber, we should see the board's answer to our fake ping: + +``` +user@user:~$ ros2 topic echo /microROS/pong +stamp: + sec: 0 + nanosec: 0 +frame_id: fake_ping +--- +``` diff --git a/_docs/tutorials/core/programming_rcl_rclc/index.md b/_docs/tutorials/core/programming_rcl_rclc/index.md index 01bbd8f4..8a83e683 100644 --- a/_docs/tutorials/core/programming_rcl_rclc/index.md +++ b/_docs/tutorials/core/programming_rcl_rclc/index.md @@ -1,8 +1,6 @@ --- title: Programming with rcl and rclc permalink: /docs/tutorials/core/programming_rcl_rclc/ -redirect_from: /docs/tutorials/core/ -redirect_from: /docs/tutorials/ --- ## Programming client/service with rcl diff --git a/_docs/tutorials/demos/crazyflie_demo/index.md b/_docs/tutorials/demos/crazyflie_demo/index.md index cc34893b..7447d116 100644 --- a/_docs/tutorials/demos/crazyflie_demo/index.md +++ b/_docs/tutorials/demos/crazyflie_demo/index.md @@ -1,302 +1,10 @@ --- title: Crazyflie Demo +layout: docs_noheader permalink: /docs/tutorials/demos/crazyflie_demo/ redirect_from: - /crazyflie_demo/ --- -This demo aims to expose a **micro-ROS** use case. It runs on a pair of embedded devices: -a [**Crazyflie 2.1**](https://www.bitcraze.io/crazyflie-2-1/) drone, used as a user controller, -and a [**Kobuki Turtlebot 2**](https://www.turtlebot.com/turtlebot2/) as a mobile and controlled device. - -![Illustration of the Crazyflie - DDS interaction](micro-ROS_crazyflie.png) - -Both of them rely on **micro-ROS** publication and subscription mechanisms and use an underlying [**Micro XRCE-DSS client**](https://micro-xrce-dds.readthedocs.io/en/latest/). - -This demo also includes conventional ROS 2 tooling as a demonstration of integration with **ROS 2**. We use Gazebo, RVIZ and simple ROS 2 nodes (aka **external nodes**) acting as data converters. - -This demo was developed taking as base the [Kobuki demo](/docs/tutorials/demos/kobuki_demo). - -## Index -- [Installation](#installation) - - [Install external ROS 2 nodes](#install-external-ros-2-nodes) - - [Build and flash Crazyflie 2.1 firmware](#build-and-flash-crazyflie-21-firmware) - - [Install Crazyflie Client + Bridge](#install-crazyflie-client--bridge) - - [Build and flash Kobuki Turtlebot 2 firmware](#build-and-flash-kobuki-turtlebot-2-firmware) -- [Usage](#usage) - - [Run Kobuki Turtlebot 2 Node](#run-kobuki-turtlebot-2-node) - - [Run Crazyflie 2.1 Node](#run-crazyflie-21-node) - - [Run external ROS 2 nodes](#run-external-ros-2-nodes) - - [Run RVIZ visualizers](#run-rviz-visualizers) - -## Setup - -The proposed demo is composed of different kind of messages and topics. - -The **Crazyflie 2.1** drone relies on [ST STM32F405](https://www.st.com/en/microcontrollers-microprocessors/stm32f405-415.html) MCU running **[FreeRTOS](https://www.freertos.org/)**. Using the RTOS capabilities and the integrated radio communication device, the drone can run a node that publishes: -- its own relative position as a 3D vector (X, Y and Z) using a *geometry_msg/Point32* message type on */drone/odometry* topic. -- its own attitude as a 3D vector (pitch, roll and yaw) using a *geometry_msg/Point32* message type on */drone/attitude* topic. - -The **Kobuki Turtlebot 2** robot is controlled using a UART protocol through a custom DB25 connector. The micro-ROS node runs on an Olimex STM32-E407 board attached to that UART port. This hardware features a [ST STM32F407](https://www.st.com/en/microcontrollers-microprocessors/stm32f407-417.html) MCU running **[Nuttx](https://nuttx.org/)** RTOS. In the same way, this node can communicate with the robot (UART) and with the ROS2 world (integrated Ethernet). Its used topics are: -- a subscription on */cmd_vel* topic (*geometry_msg/Twist* message type) to receive the controlling angular and linear velocity. -- a publication on */robot_pose* topic (*geometry_msg/Vector3* message type) which includes X position, Y position and robot yaw. - -The **external ROS 2 nodes** are rclpy tools with some different functionalities: -- *attitude_to_vel.py* - - Converts Crazyflie */drone/attitude* to Kobuki Turtlebot 2 */cmd_vel* so that drone pitch is mapped to robot linear velocity and drone roll to angular valocity. - - Converts Crazyflie publications on */drone/attitude* and */drone/attitude* topics to *tf2_msgs/TFMessage* messages (required by RVIZ visualizer) -- *odom_to_tf.py* - - Converts Kobuki Turtlebot 2 publications on */robot_pose* topic to *tf2_msgs/TFMessage* messages (required by RVIZ visualizer). - -The following image shows the described setup. - -![Kobuki_drone_demo](http://www.plantuml.com/plantuml/png/XLDHJzim47xlhp3P2wlMP0FniWS40uhGDeegreUXANAJQx18V95zBcBJ_llYIpChfDdwuChVz_axt-VBcILfo5Nbv227ZT8WRYuMjz-MNyGZKMq_9ecHpt6XwD6jdGMJeIRG56TO9UHgcPlZf2wbzXOprR2pJQEOsTee0fjiZ-8FyVl9WT9PwN9mfkpyayQXGXtNN7iFppxo6InMC3j93AwHnjK5Rdrrc-G6DRGw-wHqBOsin5fcJuL1f_CBBD68D_FvV38HpKzf0hEH6OYeFTeMIckq81xkiE6FZtw8wVJAbM34kIvAiDDf9AGL30rSiYfFjr2AXmAm0Z8lQMKBcpHBSl-iB7cp5PIOANhP6J4-C0eNsUUrWepG77ktHSvavzPjH_h37TthxWwj8eLwPz5jsQ8DwdgnIY-NYzkhmqjlyqv4_1-zPVO2gxhPQHAII97B8INqCSJro-IL8hgMFs6DuZEktPEAX2_OGcaB2JumFpz9bujFY_l35cqgxawq9Nana97qRoAYhR9EbifAV_58_6B-TGIq4G_tywzWhInWJ-D_kS7f460jwR49hrdPmC1MeGkPTTFX1UpIxzx7xxEXZOzco4VBrSrtmTcAyrsMxEVnbF5K_kTSTvNNv-hHSssoGT_kMVuxfDswpsQdOVG35eQ6SLQ8E3xTCn4iwEJ_qWnXhXI-bp51UCPHKNWWNjYJxn9w3s1_GBd3FiIElIzl7yv4jsFV_ZWm7w11Eom8MtRelzUG3LCpIeVXu526p1det5Nb7m00) - -## Required Hardware - -This setup uses the following hardware: - -| Item | | -|---------------|----------------------------------------------------------| -| Kobuki Turtlebot 2 | [Link](https://www.turtlebot.com/turtlebot2/) | -| Olimex STM32-E407 | [Link](https://www.olimex.com/Products/ARM/ST/STM32-E407/open-source-hardware) | -| Olimex ARM-USB-TINY-H | [Link](https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H/) | -| Crazyflie 2.1 | [Link](https://store.bitcraze.io/products/crazyflie-2-1) | -| Flow Desk v2 | [Link](https://store.bitcraze.io/collections/decks/products/flow-deck-v2) | -| Debug adapter | [Link](https://store.bitcraze.io/collections/accessories/products/debug-adapter) | -| Crazyradio PA 2.4 GHz USB dongle | [Link](https://store.bitcraze.io/collections/accessories/products/crazyradio-pa) | -| Additional battery + charger (optional) | [Link](https://store.bitcraze.io/collections/accessories/products/240mah-lipo-battery-including-500ma-usb-charger) | - - -# Installation - -## Install external ROS 2 nodes - -[Install Micro XCRE-DDS](https://micro-xrce-dds.readthedocs.io/en/latest/installation.html). Recommended procedure: - -```bash -git clone https://github.com/eProsima/Micro-XRCE-DDS.git -b v1.1.0 -cd Micro-XRCE-DDS -mkdir build && cd build -cmake .. -make -sudo make install -``` - -Create a workspace folder for this demo: -```bash -mkdir -p crazyflie_demo/src -cd crazyflie_demo -``` - -Clone this repo: -```bash -git clone --single-branch --branch crazyflie_demo https://github.com/micro-ROS/micro-ROS_kobuki_demo src -``` - -[Install Gazebo](http://gazebosim.org/tutorials?tut=install_ubuntu&cat=install#InstallGazebousingUbuntupackages). Recommended procedure: -```bash -curl -sSL http://get.gazebosim.org | sh -``` - -[Install gazebo_ros_pkgs (ROS 2)](http://gazebosim.org/tutorials?tut=ros2_installing&cat=connect_ros). Recommended procedure: -```bash -source /opt/ros/dashing/setup.bash -wget https://bitbucket.org/api/2.0/snippets/chapulina/geRKyA/f02dcd15c2c3b83b2d6aac00afe281162800da74/files/ros2.yaml -vcs import src < ros2.yaml -rosdep update && rosdep install --from-paths src --ignore-src -r -y -rm ros2.yaml -``` - -Build the project: -```bash -source /opt/ros/dashing/setup.bash -rosdep update && rosdep install --from-paths src --ignore-src -r -y -colcon build --symlink-install -``` - -## Build and flash Crazyflie 2.1 firmware - -Install the toolchain: -```bash -sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa -sudo apt-get update -sudo apt install gcc-arm-embedded dfu-util -``` - -Download and build the **Crazyflie 2.1** firmware repository: -```bash -mkdir crazyflie_firmware -git clone https://github.com/eProsima/crazyflie-firmware -b crazyflie_demo -cd crazyflie_firmware -git submodule init -git submodule update -make PLATFORM=cf2 -``` - -Unplug the **Crazyflie 2.1** battery - -Push the reset button while connecting the USB power supply. - -The top-left blue LED blinks, first slowly and after 4 seconds sightly faster, now it is in DFU programming mode. Check it with `lsusb`: -```bash -Bus 001 Device 051: ID 0483:df11 STMicroelectronics STM Device in DFU Mode -``` - -Flash the device: -```bash -sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D cf2.bin -``` - -Unplug and plug the **Crazyflie 2.1** power to exit DFU mode. - - -## Install Crazyflie Client + Bridge - -Install dependencies: -``` -sudo apt-get install libusb-1.0-0-dev -sudo apt-get install python3 python3-pip python3-pyqt5 python3-pyqt5.qtsvg -``` - -Fix permissions for the Crazyradio PA 2.4 GHz USB dongle (restart required for apply changes): -``` -sudo groupadd plugdev -sudo usermod -a -G plugdev $USER -sudo echo SUBSYSTEM==\"usb\", ATTRS{idVendor}==\"1915\", ATTRS{idProduct}==\"7777\", \ -MODE=\"0664\", GROUP=\"plugdev\" > /etc/udev/rules.d/99-crazyradio.rules -sudo echo SUBSYSTEM==\"usb\", ATTRS{idVendor}==\"0483\", ATTRS{idProduct}==\"5740\", \ -MODE=\"0664\", GROUP=\"plugdev\" > /etc/udev/rules.d/99-crazyflie.rules -``` - -Clone the repo dependencies: -``` -git clone -b Micro-XRCE-DDS_Bridge https://github.com/eProsima/crazyflie-clients-python -``` - -## Build and flash Kobuki Turtlebot 2 firmware - -Create a workspace for building **micro-ROS**: -``` -source /opt/ros/crystal/setup.bash -sudo apt install python-rosdep curl flex ed gperf openocd automake ed bison libncurses5-dev gcc-arm-none-eabi clang clang-tidy usbutils -mkdir -p kobuki-firmware/src -cd kobuki-firmware -git clone --recursive -b crazyflie_demo https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-build -colcon build --packages-select micro_ros_setup -source install/local_setup.bash -``` - -Build **micro-ROS Agent**: -``` -ros2 run micro_ros_setup create_agent_ws.sh -colcon build -source install/local_setup.sh -``` - -Install tools: -``` -git clone https://bitbucket.org/nuttx/tools.git ~/tools -pushd ~/tools/kconfig-frontends >/dev/null -./configure --enable-mconf --disable-nconf --disable-gconf --disable-qconf -LD_RUN_PATH=/usr/local/lib && make && make install && ldconfig -popd >/dev/null -``` - -Build Olimex STM32-E407 firmware: -``` -ros2 run micro_ros_setup create_firmware_ws.sh -cd firmware/NuttX -tools/configure.sh configs/olimex-stm32-e407/uros -cd ../.. - -#Put here your agent IP and port -find ./firmware/mcu_ws/ -name rmw_microxrcedds.config -exec sed -i "s/CONFIG_IP=127.0.0.1/CONFIG_IP=192.168.8.10/g" {} \; -find ./firmware/mcu_ws/ -name rmw_microxrcedds.config -exec sed -i "s/CONFIG_PORT=8888/CONFIG_PORT=9999/g" {} \; - -ros2 run micro_ros_setup build_firmware.sh - ``` - -Connect Olimex ARM-USB-TINY-H JTAG debugger to Olimex STM32-E407 and flash the board: -``` -cd firmware/NuttX -scripts/flash.sh olimex-stm32-e407 -``` - -# Usage - -After installation, the following packages should be present in your system: - -``` -. -+-- Micro-XRCE-DDS # used for installing Micro-XRCE-DDS -+-- crazyflie_demo -+-- crazyflie-firmware # used for building and flashing Crazyflie 2.1 firmware -+-- kobuki-firmware # used for building and flashing Kobuki Turtlebot 2 firmware -+-- crazyflie-clients-python -``` - -Make sure that all ROS 2 or micro-ROS nodes created along with the following steps **can reach each other using its network interfaces**. - -## Run Kobuki Turtlebot 2 Node - -TODO: Explain data and power connections between Kobuki Turtlebot 2, Olimex STM32-E407 and MiniRouter. - -Run the **micro-ROS Agent**: -``` -cd kobuki-firmware -source /opt/ros/crystal/setup.bash && source install/local_setup.bash -ros2 run micro_ros_agent micro_ros_agent udp 9999 -``` - -**micro-ROS Agent** should receive an incoming client connection and */robot_pose* topic should be published. Check it with `ros2 topic echo /robot_pose` - -## Run Crazyflie 2.1 Node - -Connect Crazyradio PA 2.4 GHz USB dongle and turn on Crazyflie 2.1 drone. - -Run the Crazyflie Client + Bridge: -``` -cd crazyflie-clients-python -python3 bin/cfclient -``` - -This command should open the Crazyflie Client and print a serial device path in the terminal (something like /dev/pts/0). - -Run (in another prompt) a **Micro XRCE-DDS Agent**: -``` -MicroXRCEAgent serial --dev [serial device] -``` - -**Micro XRCE-DDS Agent** should receive an incoming client connection and */drone/attitude* and */drone/position* topics should be published. Check it with `ros2 topic echo /drone/attitude` and `ros2 topic echo /drone/position` - - -## Run external ROS 2 nodes - -Run commands: -``` -cd crazyflie_demo -source /opt/ros/crystal/setup.bash && source install/local_setup.bash -ros2 run micro-ros_crazyflie_demo_remote attitude_to_vel -``` - -Topic */cmd_vel* should be published, and the **Kobuki Turtlebot 2** should start moving. Check it with `ros2 topic echo /cmd_vel` - -## Run RVIZ visualizers -Run complete visualizer: -``` -cd crazyflie_demo -source /opt/ros/crystal/setup.bash && source install/local_setup.bash -ros2 launch micro-ros_crazyflie_demo_remote launch_drone_position.launch.py -``` - -RVIZ windows should be open, and a Crazyflie 2.1 drone model should represent the drone attitude and position along with a historic path. - -Run attitude visualizer: -``` -cd crazyflie_demo -source /opt/ros/crystal/setup.bash && source install/local_setup.bash -ros2 launch micro-ros_crazyflie_demo_remote launch_drone_attitude.launch.py -``` - -RVIZ windows should be open and a Crazyflie 2.1 drone model should represent **only** the drone attitude. \ No newline at end of file +{% capture my_include %}{% include crazyflie_demo/README.md %}{% endcapture %} +{{ my_include | markdownify }} \ No newline at end of file diff --git a/_docs/tutorials/demos/crazyflie_demo/micro-ROS_crazyflie.png b/_docs/tutorials/demos/crazyflie_demo/micro-ROS_crazyflie.png deleted file mode 100644 index 0133a1ee..00000000 Binary files a/_docs/tutorials/demos/crazyflie_demo/micro-ROS_crazyflie.png and /dev/null differ diff --git a/_docs/tutorials/demos/tof_demo/index.md b/_docs/tutorials/demos/tof_demo/index.md index 5dc4a63a..f9a4d19d 100644 --- a/_docs/tutorials/demos/tof_demo/index.md +++ b/_docs/tutorials/demos/tof_demo/index.md @@ -1,5 +1,8 @@ --- title: Time of Flight Sensor Demo +layout: docs_noheader permalink: /docs/tutorials/demos/tof_demo/ --- -WIP \ No newline at end of file + +{% capture my_include %}{% include sensors_demo/README.md %}{% endcapture %} +{{ my_include | markdownify }} \ No newline at end of file diff --git a/_includes/crazyflie_demo b/_includes/crazyflie_demo new file mode 160000 index 00000000..841122e4 --- /dev/null +++ b/_includes/crazyflie_demo @@ -0,0 +1 @@ +Subproject commit 841122e49651a85d3e0d07fc01b9a2857c4cff99 diff --git a/_includes/sensors_demo b/_includes/sensors_demo new file mode 160000 index 00000000..12bb858d --- /dev/null +++ b/_includes/sensors_demo @@ -0,0 +1 @@ +Subproject commit 12bb858d105897dacf193516194ed059c31819c9 diff --git a/_layouts/docs_noheader.html b/_layouts/docs_noheader.html new file mode 100644 index 00000000..2fbd6a39 --- /dev/null +++ b/_layouts/docs_noheader.html @@ -0,0 +1,26 @@ +--- +layout: default +--- + +
+
+
+ {% include docs_nav.html %} +
+ +
+
{{ content }}
+ +
+ {% include section_nav.html %} +
+ +
+
diff --git a/_posts/2020-03-03-micro-ROS-at-ERF2020.md b/_posts/2020-03-03-micro-ROS-at-ERF2020.md index 23810700..e5207940 100644 --- a/_posts/2020-03-03-micro-ROS-at-ERF2020.md +++ b/_posts/2020-03-03-micro-ROS-at-ERF2020.md @@ -11,6 +11,6 @@ All partners of the EU project behind micro-ROS together organized a booth to di Our booth attracted a lot of interest: Many attendees visited us not only to talk about the demos and the status of micro-ROS, but also to discuss on the latest ROS 2 developments. -In the ERF workshop on "Overcoming the boundaries of today's Robotics Software Engineering", Ralph Lange from Bosch Corporate Research also had the possibility to provide a short update on micro-ROS. +In the ERF workshop on "Overcoming the boundaries of today's Robotics Software Engineering", Ralph Lange from Bosch Corporate Research also had the possibility to provide a [short update on micro-ROS](/download/2020-03-04_micro-ROS_talk_at_ERF.pdf). diff --git a/scripts/cibuild b/scripts/cibuild index 1e54f559..a4e1cc38 100755 --- a/scripts/cibuild +++ b/scripts/cibuild @@ -20,4 +20,4 @@ IGNORE_HREFS=${IGNORE_HREFS:+$IGNORE_HREFS,}$(ruby -e "puts %w{ echo "Ignoring urls: " $IGNORE_HREFS bundle exec jekyll build -bundle exec htmlproofer --check_html --check-favicon --assume-extension --empty-alt-ignore --only-4xx --url-ignore $IGNORE_HREFS $@ ./_site \ No newline at end of file +bundle exec htmlproofer --check_html --http-status-ignore "429" --check-favicon --assume-extension --empty-alt-ignore --only-4xx --url-ignore $IGNORE_HREFS $@ ./_site \ No newline at end of file