Tüm eğitimler
TEKNİK REHBERGÖMÜLÜ LİNUXROBOTİK2026

ROS 2
Gömülü Robot İşletim Sistemi

ROS 2'nin Raspberry Pi ve i.MX8 gibi gömülü platformlarda kurulumu, cross-compilation, gerçek zamanlı executor, micro-ROS ile MCU entegrasyonu ve gömülü sensör uygulamaları.

00 ROS 2 Gömülü Motivasyonu

ROS 1'in 2025 sonunda ömrünü tamamlaması ve ROS 2'nin DDS tabanlı dağıtık mimarisi, gömülü robot platformları için kaçınılmaz geçişi hızlandırdı.

ROS 1'den ROS 2'ye Geçiş Motivasyonu

ROS 1 EOLROS Noetic (son ROS 1 sürümü) Mayıs 2025'te ömrünü tamamladı; yeni projeler için artık desteklenmiyor
DDS tabanlı iletişimMerkezi rosmaster bağımlılığı ortadan kalktı; dağıtık keşif ile SPOF sorunu çözüldü
Gerçek zamanlı destekSCHED_FIFO entegrasyonu, belirlenimci executor ve önceden atanmış bellek yönetimi eklendi
Çapraz platformLinux, macOS, Windows ve RTOS desteği; micro-ROS ile MCU'lar da ROS 2 ağına dahil edilebilir
GüvenlikDDS Security ile uçtan uca şifreleme ve erişim kontrolü; otonom araç ve tıbbi robotlar için kritik

ROS 2 Mimari Katmanları

Kullanici uygulamasi (C++ / Python)
          |
    rclcpp / rclpy
          |
    rcl (C kutuphanesi)
          |
    rmw API (middleware soyutlamasi)
    /           \           \
rmw_fastrtps  rmw_cyclone  rmw_connext
(Fast-DDS)   (CycloneDDS)  (RTI)
          |
   DDS / RTPS wire protokol
          |
   UDP / TCP (veya SHM)
  

Desteklenen Gömülü Platformlar

PlatformİşlemciROS 2 DurumNotlar
Raspberry Pi 4/5ARM Cortex-A72/A76Tam destekUbuntu 22.04 ARM64 önerilir
i.MX 8M PlusARM Cortex-A53Tam destekNPU hızlandırma ile birlikte kullanılabilir
NVIDIA Jetson NanoARM Cortex-A57Tam destekNVIDIA Isaac ROS eklentileri mevcuttur
BeagleBone AI-64ARM Cortex-A72Topluluk desteğiTDA4VM DSP entegrasyonu gerekli
STM32 (MCU)Cortex-M4/M7micro-ROSFreeRTOS veya Zephyr gerektirir

ROS 1 ile ROS 2 Karşılaştırması

ÖzellikROS 1ROS 2
İletişim altyapısıTCPROS / UDPROS (özel)DDS / RTPS (standart)
Merkezi bileşenrosmaster (SPOF)Yok — dağıtık keşif
Gerçek zamanlıSınırlıStaticSingleThreadedExecutor + SCHED_FIFO
GüvenlikYokDDS Security (X.509, AES-GCM)
MCU desteğirosserial (sınırlı)micro-ROS (tam DDS entegrasyonu)
Yaşam döngüsüROS Noetic EOL Mayıs 2025Humble LTS 2027, Jazzy LTS 2029

01 Gömülü Platform Hazırlığı

Gömülü Linux üzerinde ROS 2 çalıştırmak için Ubuntu ARM64 kurulumu, Yocto ile meta-ros katmanı veya Docker tabanlı dağıtım yöntemleri kullanılır.

Raspberry Pi 4 — Ubuntu 22.04 ARM64

# Ubuntu 22.04 Server ARM64 imajini SD kartina yaz
# Imaj: ubuntu-22.04.4-preinstalled-server-arm64+raspi.img.xz

# ROS 2 Humble (LTS -- 2027'ye kadar destek) kurulumu
sudo apt update && sudo apt install -y curl gnupg lsb-release
sudo curl -sSL \
    https://raw.githubusercontent.com/ros/rosdistro/master/ros.key \
    -o /usr/share/keyrings/ros-archive-keyring.gpg

echo "deb [arch=$(dpkg --print-architecture) \
    signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] \
    http://packages.ros.org/ros2/ubuntu \
    $(lsb_release -cs) main" \
    | sudo tee /etc/apt/sources.list.d/ros2.list

sudo apt update

# Minimal kurulum (gomulu icin onerilir)
sudo apt install ros-humble-ros-base
# Gelistirme araclari ile tam kurulum (x86 gelistirme makinesi)
sudo apt install ros-humble-desktop-full
sudo apt install python3-colcon-common-extensions

# Ortam degiskeni
source /opt/ros/humble/setup.bash
echo "source /opt/ros/humble/setup.bash" >> ~/.bashrc

Yocto meta-ros ile Minimal İmaj

# meta-ros katmanini ekle
git clone -b humble https://github.com/ros/meta-ros.git

# bblayers.conf
BBLAYERS += " \
  /path/to/meta-ros/meta-ros2         \
  /path/to/meta-ros/meta-ros2-humble  \
"

# local.conf -- minimal gomulu ROS 2
MACHINE = "raspberrypi4-64"

# Yalnizca temel ROS 2 runtime
IMAGE_INSTALL:append = " \
    ros-humble-ros-base \
    ros-humble-rmw-cyclonedds-cpp \
    ros-humble-rclcpp \
"

# Opsiyonel: sensor mesajlari
IMAGE_INSTALL:append = " \
    ros-humble-sensor-msgs \
    ros-humble-geometry-msgs \
"

# Derleme
bitbake core-image-minimal

Docker Tabanlı Hızlı Başlangıç

# ARM64 icin resmi ROS 2 Humble imaji
docker pull ros:humble-ros-base-jammy

# Raspberry Pi uzerinde calistir
docker run --rm -it \
    --network host \
    --device /dev/i2c-1:/dev/i2c-1 \
    --device /dev/ttyUSB0:/dev/ttyUSB0 \
    ros:humble-ros-base-jammy \
    bash

# Container icinde ROS 2 ortamini yukle
source /opt/ros/humble/setup.bash
ros2 topic list

Sistem Gereksinimleri

BileşenMinimumÖnerilenNotlar
RAM512 MB2 GB+ros-base ~150 MB, desktop ~800 MB
Depolama4 GB16 GB+Log dosyaları ve paket depolaması
İşlemciCortex-A7 (1 GHz)Cortex-A53+ (1.5 GHz+)DDS discovery CPU yoğun
İşletim SistemiUbuntu 22.04 ARM64Ubuntu 22.04 ARM64Yocto kirkstone+ da desteklenir

02 Cross-Compilation

ROS 2 paketlerini geliştirme makinesinde hedef platform için çapraz derlemek, gerçek donanım olmadan hızlı geliştirme ve CI/CD entegrasyonu sağlar.

Cross-Compilation Yöntemleri

QEMU binfmt + colconQEMU ARM64 emülasyonu ile doğrudan hedef mimarisi için derleme; yavaş ama kolay kurulum
Toolchain + sysrootGerçek cross-compiler ile hızlı derleme; sysroot hazırlama ilk seferinde karmaşık olabilir
Docker buildx multiarchDocker buildx ile ARM64 imajı oluşturma; CI/CD entegrasyonu en kolay yöntem

QEMU binfmt ile Cross-Compile

# QEMU ve binfmt kurulumu (Ubuntu x86_64 gelistirme makinesi)
sudo apt install qemu-user-static binfmt-support
sudo update-binfmts --enable qemu-aarch64

# ARM64 Docker imajini calistir (QEMU ile transparan emulasyon)
docker run --rm -it \
    --platform linux/arm64 \
    -v $(pwd):/workspace \
    ros:humble-ros-base-jammy bash

# Imaj icinde colcon ile derle
cd /workspace
source /opt/ros/humble/setup.bash
colcon build \
    --packages-select my_sensor_pkg \
    --cmake-args -DCMAKE_BUILD_TYPE=Release

Toolchain.cmake ile Gerçek Cross-Compile

# toolchain-rpi4.cmake
set(CMAKE_SYSTEM_NAME Linux)
set(CMAKE_SYSTEM_PROCESSOR aarch64)

set(CMAKE_C_COMPILER   aarch64-linux-gnu-gcc)
set(CMAKE_CXX_COMPILER aarch64-linux-gnu-g++)

# Raspberry Pi sysroot (NFS veya rsync ile kopyalanmis rootfs)
set(CMAKE_SYSROOT /opt/rpi4-sysroot)
set(CMAKE_FIND_ROOT_PATH /opt/rpi4-sysroot)
set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)

# ROS 2 paketleri icin ek arama yolu
list(APPEND CMAKE_PREFIX_PATH
    /opt/rpi4-sysroot/opt/ros/humble)
# Cross-compile komutu
source /opt/ros/humble/setup.bash

colcon build \
    --packages-select my_sensor_pkg \
    --cmake-args \
        -DCMAKE_TOOLCHAIN_FILE=/path/to/toolchain-rpi4.cmake \
        -DCMAKE_BUILD_TYPE=Release \
        -DBUILD_TESTING=OFF

# Derlenen binary'leri hedefe kopyala
rsync -avz install/ pi@raspberrypi:/home/pi/ros2_ws/install/

# Hedefte calistir
ssh pi@raspberrypi
source /opt/ros/humble/setup.bash
source /home/pi/ros2_ws/install/setup.bash
ros2 run my_sensor_pkg temp_publisher

package.xml — Minimal Bağımlılıklar

<package format="3">
  <name>my_sensor_pkg</name>
  <version>0.1.0</version>
  <description>Gomulu IMU sensor paketi</description>
  <maintainer email="emirpehlevan@gmail.com">Emirhan</maintainer>
  <license>Apache-2.0</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>
  <depend>sensor_msgs</depend>
  <depend>std_msgs</depend>
  <depend>tf2_ros</depend>
</package>

03 Node ve Topic Temelleri

rclcpp::Node temel yapı taşıdır. create_publisher ve create_subscription metotları ile topic üzerinde yayın ve abonelik oluşturulur.

Temel Node — Sıcaklık Yayıncısı

#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/temperature.hpp"
#include <chrono>
#include <memory>

using namespace std::chrono_literals;

class TemperaturePublisher : public rclcpp::Node
{
public:
    explicit TemperaturePublisher()
        : Node("temperature_publisher"), count_(0)
    {
        /* QoS profili: en iyi caba, sensor verisi icin */
        auto qos = rclcpp::SensorDataQoS();

        publisher_ = this->create_publisher<
            sensor_msgs::msg::Temperature>(
                "sensor/temperature", qos);

        /* 500 ms'de bir yayinla */
        timer_ = this->create_wall_timer(
            500ms,
            std::bind(&TemperaturePublisher::timer_callback,
                      this));

        RCLCPP_INFO(this->get_logger(),
                    "Sicaklik yayincisi baslatildi");
    }

private:
    void timer_callback()
    {
        auto msg = sensor_msgs::msg::Temperature();
        msg.header.stamp    = this->now();
        msg.header.frame_id = "temperature_sensor";
        msg.temperature     = 22.5 + 0.1 * count_;
        msg.variance        = 0.01;

        publisher_->publish(msg);
        RCLCPP_DEBUG(this->get_logger(),
                     "Gonderildi: %.2f C", msg.temperature);
        count_++;
    }

    rclcpp::Publisher<sensor_msgs::msg::Temperature>::SharedPtr
        publisher_;
    rclcpp::TimerBase::SharedPtr timer_;
    size_t count_;
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<TemperaturePublisher>());
    rclcpp::shutdown();
    return 0;
}

Abone Node — Eşik Alarm Kontrolü

#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/temperature.hpp"
#include "std_msgs/msg/bool.hpp"

class AlarmController : public rclcpp::Node
{
public:
    explicit AlarmController()
        : Node("alarm_controller"), threshold_(30.0)
    {
        sub_ = this->create_subscription<
            sensor_msgs::msg::Temperature>(
                "sensor/temperature",
                rclcpp::SensorDataQoS(),
                std::bind(&AlarmController::on_temperature,
                          this, std::placeholders::_1));

        alarm_pub_ = this->create_publisher<
            std_msgs::msg::Bool>(
                "alarm/temperature_high",
                rclcpp::QoS(10).reliable());

        this->declare_parameter("threshold", threshold_);
    }

private:
    void on_temperature(
        const sensor_msgs::msg::Temperature::SharedPtr msg)
    {
        threshold_ =
            this->get_parameter("threshold").as_double();

        auto alarm = std_msgs::msg::Bool();
        alarm.data = (msg->temperature > threshold_);
        alarm_pub_->publish(alarm);

        if (alarm.data) {
            RCLCPP_WARN(this->get_logger(),
                        "ALARM: %.2f C > esik %.2f C",
                        msg->temperature, threshold_);
        }
    }

    rclcpp::Subscription<sensor_msgs::msg::Temperature>::SharedPtr
        sub_;
    rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr alarm_pub_;
    double threshold_;
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<AlarmController>());
    rclcpp::shutdown();
    return 0;
}

CMakeLists.txt

cmake_minimum_required(VERSION 3.16)
project(my_sensor_pkg)

find_package(ament_cmake REQUIRED)
find_package(rclcpp      REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs    REQUIRED)

add_executable(temp_publisher  src/temperature_publisher.cpp)
ament_target_dependencies(temp_publisher rclcpp sensor_msgs)

add_executable(alarm_controller src/alarm_controller.cpp)
ament_target_dependencies(alarm_controller
    rclcpp sensor_msgs std_msgs)

install(TARGETS temp_publisher alarm_controller
    DESTINATION lib/my_sensor_pkg)

ament_package()

Hızlı Test

# Terminan 1: yayinci
source /opt/ros/humble/setup.bash
ros2 run my_sensor_pkg temp_publisher

# Terminal 2: abone ile izle
ros2 topic echo /sensor/temperature

# Terminal 3: alarm kontrolcu
ros2 run my_sensor_pkg alarm_controller --ros-args \
    -p threshold:=28.0

04 Gerçek Zamanlı Executor

ROS 2'nin StaticSingleThreadedExecutor'ı belirlenimci yürütme düzeni sağlar. SCHED_FIFO ile birleştirildiğinde gerçek zamanlı gömülü sistemler için uygun bir çerçeve oluşur.

Executor Türleri Karşılaştırması

MultiThreadedExecutorBirden fazla thread; yük dengeleme için iyi ancak öncelik yönetimi karmaşık
SingleThreadedExecutorTek thread; belirlenimci ama dinamik callback listesi yönetim yükü var
StaticSingleThreadedExecutorSabit callback listesi; gerçek zamanlı için en uygun; en düşük overhead
EventsExecutor (ROS 2 Iron+)Olay tabanlı; bekleme döngüsü yok; en düşük gecikme potansiyeli

SCHED_FIFO ile Gerçek Zamanlı Node

#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include <sched.h>
#include <sys/mman.h>

/* Gercek zamanli oncelik ayarlama */
bool configure_realtime(int priority)
{
    struct sched_param param;
    param.sched_priority = priority;

    /* SCHED_FIFO: kesintisiz on once calıstırma */
    if (sched_setscheduler(0, SCHED_FIFO, &param) != 0) {
        perror("sched_setscheduler basarisiz");
        return false;
    }

    /* Bellek kilitleme: swap'i engelle */
    if (mlockall(MCL_CURRENT | MCL_FUTURE) != 0) {
        perror("mlockall basarisiz");
        return false;
    }

    return true;
}

class RealtimeImuPublisher : public rclcpp::Node
{
public:
    RealtimeImuPublisher()
        : Node("rt_imu_publisher",
               rclcpp::NodeOptions()
                   .use_intra_process_comms(true))
    {
        /* Best-effort, 1 derinlik -- en dusuk gecikme */
        auto qos = rclcpp::QoS(1)
            .best_effort()
            .durability_volatile();

        publisher_ = this->create_publisher<
            sensor_msgs::msg::Imu>("imu/data_raw", qos);

        /* 1 kHz IMU okuma zamanlayicisi */
        timer_ = this->create_wall_timer(
            std::chrono::microseconds(1000),
            std::bind(&RealtimeImuPublisher::publish_imu,
                      this));

        RCLCPP_INFO(this->get_logger(),
                    "RT IMU yayinci baslatildi (1 kHz)");
    }

private:
    void publish_imu()
    {
        auto msg = sensor_msgs::msg::Imu();
        msg.header.stamp    = this->now();
        msg.header.frame_id = "imu_link";

        /* read_imu_hardware: SPI/I2C surucusu cagrisi */
        read_imu_hardware(
            &msg.linear_acceleration.x,
            &msg.linear_acceleration.y,
            &msg.linear_acceleration.z,
            &msg.angular_velocity.x,
            &msg.angular_velocity.y,
            &msg.angular_velocity.z);

        publisher_->publish(msg);
    }

    rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr publisher_;
    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);

    /* Gercek zamanli oncelik ayarla (root gerektirir) */
    if (!configure_realtime(80)) {
        RCLCPP_WARN(rclcpp::get_logger("main"),
                    "RT oncelik ayarlanamadi, devam ediliyor");
    }

    auto node = std::make_shared<RealtimeImuPublisher>();

    /* StaticSingleThreadedExecutor -- en belirlenimci */
    rclcpp::executors::StaticSingleThreadedExecutor executor;
    executor.add_node(node);
    executor.spin();

    rclcpp::shutdown();
    return 0;
}

systemd Servisi ile RT Öncelik

# /etc/systemd/system/ros2-imu.service
[Unit]
Description=ROS 2 IMU Node (Gercek Zamanli)
After=network.target

[Service]
Type=simple
User=root
Environment="RMW_IMPLEMENTATION=rmw_cyclonedds_cpp"
ExecStart=/bin/bash -c "source /opt/ros/humble/setup.bash \
    && /opt/ros2_ws/install/my_sensor_pkg/lib/my_sensor_pkg/rt_imu_publisher"
CPUSchedulingPolicy=fifo
CPUSchedulingPriority=80
LimitMEMLOCK=infinity
Restart=on-failure

[Install]
WantedBy=multi-user.target

05 micro-ROS ile MCU Entegrasyonu

micro-ROS, STM32 ve ESP32 gibi mikrodenetleyicileri ROS 2 ağına bağlar. FreeRTOS üzerinde çalışan micro-ROS istemcisi, Linux'taki micro-ROS Agent aracılığıyla tam ROS 2 varlıkları oluşturur.

micro-ROS Mimarisi

[STM32 / ESP32 -- FreeRTOS]    [Linux -- ROS 2]
 micro_ros_freertos              micro_ros_agent
    |                                 |
    |---(UART / UDP / USB)--XRCE----->|--- ROS 2 DDS -->
    |   Micro XRCE-DDS                |<-- ROS 2 DDS --
    |<--------------------------------|
  

Linux'ta micro-ROS Agent Kurulumu

# ROS 2 Humble ile hazir paket kurulumu
sudo apt install ros-humble-micro-ros-agent

# UART agent (STM32 USB UART)
source /opt/ros/humble/setup.bash
ros2 run micro_ros_agent micro_ros_agent serial \
    --dev /dev/ttyUSB0 -b 115200

# UDP agent (ESP32 Wi-Fi)
ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888

# Agent calistiktan sonra MCU'yu bagla ve dogrula
ros2 topic list
# /sensor/temperature
# /rosout

STM32 — FreeRTOS micro-ROS Görevi

#include <micro_ros_arduino.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <sensor_msgs/msg/temperature.h>

rcl_publisher_t publisher;
sensor_msgs__msg__Temperature temp_msg;
rclc_executor_t executor;
rclc_support_t  support;
rcl_allocator_t allocator;
rcl_node_t      node;
rcl_timer_t     timer;

#define RCCHECK(fn) { rcl_ret_t rc = (fn); \
    if (rc != RCL_RET_OK) error_loop(); }

void error_loop() {
    while(1) {
        HAL_GPIO_TogglePin(LED_GPIO, LED_PIN);
        HAL_Delay(100);
    }
}

void timer_callback(rcl_timer_t *t, int64_t last_call_time)
{
    (void)t; (void)last_call_time;

    temp_msg.temperature = read_adc_celsius();
    temp_msg.variance    = 0.01f;

    int64_t time_ns = rmw_uros_epoch_nanos();
    temp_msg.header.stamp.sec     = time_ns / 1000000000LL;
    temp_msg.header.stamp.nanosec = time_ns % 1000000000LL;

    RCCHECK(rcl_publish(&publisher, &temp_msg, NULL));
}

void micro_ros_task(void *arg)
{
    /* UART transport baglantisi */
    set_microros_transports();
    allocator = rcl_get_default_allocator();

    RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
    RCCHECK(rclc_node_init_default(&node,
        "stm32_sensor_node", "", &support));

    RCCHECK(rclc_publisher_init_default(
        &publisher, &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(
            sensor_msgs, msg, Temperature),
        "sensor/temperature"));

    /* Mesaj baslangic degerleri */
    sensor_msgs__msg__Temperature__init(&temp_msg);
    rosidl_runtime_c__String__assign(
        &temp_msg.header.frame_id, "stm32_temp_sensor");

    /* 1 Hz zamanlayici */
    RCCHECK(rclc_timer_init_default(
        &timer, &support,
        RCL_MS_TO_NS(1000),
        timer_callback));

    /* Executor: 1 callback */
    RCCHECK(rclc_executor_init(
        &executor, &support.context, 1, &allocator));
    RCCHECK(rclc_executor_add_timer(&executor, &timer));

    while(1) {
        rclc_executor_spin_some(&executor,
                                RCL_MS_TO_NS(100));
        vTaskDelay(pdMS_TO_TICKS(10));
    }
}

MCU ile ROS 2 Zaman Senkronizasyonu

/* MCU zamanini agent ile senkronize et */
void sync_time_with_agent(void)
{
    /* 10 oturum boyunca senkronizasyon yap */
    RCCHECK(rmw_uros_sync_session(1000));

    int64_t time_ns = rmw_uros_epoch_nanos();
    printf("ROS 2 zamani: %lld ns\n", (long long)time_ns);
}

06 Launch Sistemi ve Parameter Server

ROS 2 launch.py dosyaları birden fazla node'u tek komutla başlatır, parametreleri merkezi yönetir ve namespace'lerle çakışmaları önler.

Launch Dosyası — Sensör Sistemi

# launch/sensor_system.launch.py
from launch import LaunchDescription
from launch.actions import (
    DeclareLaunchArgument,
    GroupAction,
    SetEnvironmentVariable,
)
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node, PushRosNamespace

def generate_launch_description():
    threshold_arg = DeclareLaunchArgument(
        "temperature_threshold",
        default_value="30.0",
        description="Sicaklik alarm esigi (Celsius)"
    )
    rmw_arg = DeclareLaunchArgument(
        "rmw_impl",
        default_value="rmw_cyclonedds_cpp",
    )

    set_rmw = SetEnvironmentVariable(
        "RMW_IMPLEMENTATION",
        LaunchConfiguration("rmw_impl")
    )

    sensor_group = GroupAction([
        PushRosNamespace("robot1"),

        Node(
            package    = "my_sensor_pkg",
            executable = "temp_publisher",
            name       = "temperature_publisher",
            parameters = [{
                "publish_rate": 2.0,
                "sensor_id":    "rpi4-sensor-01",
            }],
        ),

        Node(
            package    = "my_sensor_pkg",
            executable = "alarm_controller",
            name       = "alarm_controller",
            parameters = [{
                "threshold": LaunchConfiguration(
                    "temperature_threshold"),
            }],
        ),
    ])

    return LaunchDescription([
        threshold_arg,
        rmw_arg,
        set_rmw,
        sensor_group,
    ])

Launch Dosyasını Çalıştırma

# Varsayilan parametrelerle calistir
ros2 launch my_sensor_pkg sensor_system.launch.py

# Parametre gec
ros2 launch my_sensor_pkg sensor_system.launch.py \
    temperature_threshold:=35.0 \
    rmw_impl:=rmw_fastrtps_cpp

# Calistirilan node'lari listele
ros2 node list
# /robot1/temperature_publisher
# /robot1/alarm_controller

Parameter Server ile Çalışma Zamanı Yapılandırması

# Parametre listesi
ros2 param list /robot1/alarm_controller
# threshold
# use_sim_time

# Parametre okuma
ros2 param get /robot1/alarm_controller threshold
# Double value is: 30.0

# Parametre guncelleme (calisirken)
ros2 param set /robot1/alarm_controller threshold 32.5
# Set parameter successful

# Parametreleri YAML dosyasina kaydet
ros2 param dump /robot1/alarm_controller \
    --output-dir /etc/ros2_params/

# Parametreleri YAML'dan yukle
ros2 param load /robot1/alarm_controller \
    /etc/ros2_params/robot1__alarm_controller.yaml

07 Gömülü Sensör Örneği: IMU

Raspberry Pi üzerinde MPU-6050 IMU sensörü I2C üzerinden okunarak sensor_msgs/Imu mesajı yayınlanır ve tf2 ile robot koordinat dönüşümleri tanımlanır.

MPU-6050 I2C Okuma Node'u

#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include <linux/i2c-dev.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include <unistd.h>
#include <cmath>

#define MPU6050_ADDR      0x68
#define PWR_MGMT_1        0x6B
#define ACCEL_XOUT_H      0x3B
#define ACCEL_SCALE_2G    16384.0f
#define GYRO_SCALE_250DPS 131.0f

class Mpu6050Node : public rclcpp::Node
{
public:
    Mpu6050Node() : Node("mpu6050_node"), i2c_fd_(-1)
    {
        this->declare_parameter("i2c_bus",    "/dev/i2c-1");
        this->declare_parameter("frame_id",   "imu_link");
        this->declare_parameter("publish_rate", 100.0);

        std::string bus =
            this->get_parameter("i2c_bus").as_string();
        frame_id_ =
            this->get_parameter("frame_id").as_string();
        double rate =
            this->get_parameter("publish_rate").as_double();

        if (!init_i2c(bus)) {
            RCLCPP_FATAL(this->get_logger(),
                         "I2C baslatilamadi: %s", bus.c_str());
            throw std::runtime_error("I2C init failed");
        }

        publisher_ = this->create_publisher<
            sensor_msgs::msg::Imu>(
                "imu/data_raw", rclcpp::SensorDataQoS());

        auto period = std::chrono::duration<double>(1.0/rate);
        timer_ = this->create_wall_timer(
            std::chrono::duration_cast<
                std::chrono::nanoseconds>(period),
            std::bind(&Mpu6050Node::read_and_publish, this));

        RCLCPP_INFO(this->get_logger(),
                    "MPU-6050 baslatildi (%.0f Hz)", rate);
    }

    ~Mpu6050Node() {
        if (i2c_fd_ >= 0) close(i2c_fd_);
    }

private:
    bool init_i2c(const std::string &bus)
    {
        i2c_fd_ = open(bus.c_str(), O_RDWR);
        if (i2c_fd_ < 0) return false;
        if (ioctl(i2c_fd_, I2C_SLAVE, MPU6050_ADDR) < 0)
            return false;

        /* Uyku modundan cik */
        uint8_t buf[2] = { PWR_MGMT_1, 0x00 };
        write(i2c_fd_, buf, 2);
        return true;
    }

    void read_and_publish()
    {
        /* 14 bayt ham veri oku */
        uint8_t reg = ACCEL_XOUT_H;
        write(i2c_fd_, &reg, 1);
        uint8_t buf[14];
        read(i2c_fd_, buf, 14);

        int16_t ax = (buf[0]  << 8) | buf[1];
        int16_t ay = (buf[2]  << 8) | buf[3];
        int16_t az = (buf[4]  << 8) | buf[5];
        int16_t gx = (buf[8]  << 8) | buf[9];
        int16_t gy = (buf[10] << 8) | buf[11];
        int16_t gz = (buf[12] << 8) | buf[13];

        auto msg = sensor_msgs::msg::Imu();
        msg.header.stamp    = this->now();
        msg.header.frame_id = frame_id_;

        /* m/s^2 cinsine donustur */
        const float g = 9.80665f;
        msg.linear_acceleration.x = ax / ACCEL_SCALE_2G * g;
        msg.linear_acceleration.y = ay / ACCEL_SCALE_2G * g;
        msg.linear_acceleration.z = az / ACCEL_SCALE_2G * g;

        /* rad/s cinsine donustur */
        const float d2r = M_PI / 180.0f;
        msg.angular_velocity.x = gx / GYRO_SCALE_250DPS * d2r;
        msg.angular_velocity.y = gy / GYRO_SCALE_250DPS * d2r;
        msg.angular_velocity.z = gz / GYRO_SCALE_250DPS * d2r;

        /* Kovaryans matrisleri */
        msg.orientation_covariance[0]         = -1.0; /* bilinmiyor */
        msg.linear_acceleration_covariance[0] =  0.01;
        msg.angular_velocity_covariance[0]    =  0.001;

        publisher_->publish(msg);
    }

    rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr publisher_;
    rclcpp::TimerBase::SharedPtr timer_;
    std::string frame_id_;
    int i2c_fd_;
};

tf2 Statik Dönüşüm Yayını

# IMU birimini robot govdesine gore konumlandir
# Komut satirindan:
ros2 run tf2_ros static_transform_publisher \
    0.1 0.0 0.05 \
    0.0 0.0 0.0 1.0 \
    base_link imu_link

# Veya launch.py icinde:
from launch_ros.actions import Node

tf_node = Node(
    package    = "tf2_ros",
    executable = "static_transform_publisher",
    arguments  = [
        "0.1", "0.0", "0.05",   # Konum: x y z
        "0.0", "0.0", "0.0", "1.0",  # Kuaterniyon: qx qy qz qw
        "base_link", "imu_link",
    ],
)

08 Hata Ayıklama

ros2 CLI araçları, rqt_graph görsel izleme, rosbag2 kayıt ve latency ölçümü gömülü ROS 2 sistemlerinde sorun tespitini kolaylaştırır.

ros2 CLI Araçları

# Topic listesi ve ayrinti
ros2 topic list
ros2 topic info /sensor/temperature --verbose
# Type: sensor_msgs/msg/Temperature
# Publisher count: 1
# Subscription count: 1

# Veri izle
ros2 topic echo /sensor/temperature
ros2 topic echo /imu/data_raw --field linear_acceleration

# Yayin hizi olcumu
ros2 topic hz /sensor/temperature
# average rate: 2.000 Hz

ros2 topic hz /imu/data_raw
# average rate: 99.98 Hz

# Bant genisligi
ros2 topic bw /imu/data_raw
# 28.5 KB/s

# Node bilgisi (publisher'lar, subscriber'lar, parametreler)
ros2 node info /robot1/temperature_publisher

rqt Araçları ile Görsel İzleme

# Node ve topic baglantilarini goster
rqt_graph

# Gercek zamanli grafik (sicaklik verisi)
rqt_plot /sensor/temperature/temperature

# Log mesajlarini izle
rqt_console

# Parametre degistirme UI'i
ros2 run rqt_reconfigure rqt_reconfigure

rosbag2 ile Kayıt ve Oynatma

# Tum topic'leri kaydet
ros2 bag record -a -o sensor_data_$(date +%Y%m%d_%H%M%S)

# Belirli topic'leri kaydet
ros2 bag record \
    /sensor/temperature \
    /imu/data_raw \
    -o imu_session_01

# Kayit bilgisi
ros2 bag info imu_session_01/
# Messages: 12000
# Duration: 120s
# Topic: /imu/data_raw | sensor_msgs/msg/Imu | 12000 mesaj

# Kaydi oynat (0.5x hizda)
ros2 bag play imu_session_01/ --rate 0.5

# Belirli aralik
ros2 bag play imu_session_01/ \
    --start-offset 10.0 --duration 30.0

Gecikme Ölçümü ve Performans

# Topic gecikmesi (header.stamp ile karsilastirir)
ros2 topic delay /imu/data_raw
# average delay: 0.00312 s (3.12 ms)
# min: 0.00120 s
# max: 0.00890 s

# CPU ve bellek kullanimi
top -p $(pgrep -f rt_imu_publisher)

# Gercek zamanli latency testi (Linux RT yaması ile)
sudo cyclictest -t1 -p80 -n -i 1000 -l 10000
# T:0 (PRIO:80) I:1000 C:10000 Min:12 Avg:15 Max:45 us

Yaygın Sorunlar ve Çözümleri

SorunOlası NedenÇözüm
Node'lar birbirini görmüyorROS_DOMAIN_ID farklıexport ROS_DOMAIN_ID=0 ile eşleştir
Yüksek gecikme (aynı makine)UDP, SHM etkin değilCycloneDDS SharedMemory transport etkinleştir
micro-ROS bağlantısı kopuyorUART baud rate uyumsuzluğuAgent ve MCU tarafını aynı baud rate'e eşleştir
SCHED_FIFO izin hatasıRoot yetkisi yoksudo ile çalıştır veya /etc/security/limits.conf ayarla
IMU verisi NaN değerleriI2C okuma hatasıi2cdetect -y 1 ile 0x68 adresini doğrula
rosbag2 eksik mesajlarBEST_EFFORT kayıpKayıt için RELIABLE QoS kullan