
LiDAR - Livox Mid360
--------------------

The B2W is equipped with dual Livox Mid360 LiDAR sensors for 3D perception.

**Network Configuration:**

.. list-table::
   :header-rows: 1
   :widths: 40 40

   * - Sensor
     - IP Address
   * - Livox Mid360 (Front)
     - 192.168.123.120
   * - Livox Mid360 (Rear)
     - 192.168.123.121

**Launch Options:**

.. code-block:: bash

   # Launch both LiDARs
   ros2 launch b2_lidars livox_mid360.launch.py lidar_position:=both

   # Launch front only
   ros2 launch b2_lidars livox_mid360.launch.py lidar_position:=front

   # Launch rear only
   ros2 launch b2_lidars livox_mid360.launch.py lidar_position:=rear

**Launch Arguments:**

.. list-table::
   :header-rows: 1
   :widths: 25 20 40

   * - Argument
     - Default
     - Description
   * - lidar_position
     - both
     - front, rear, or both
   * - xfer_format
     - 0
     - Data transfer format
   * - publish_freq
     - 10.0
     - Publishing frequency (Hz)
   * - namespace
     - -
     - Topic namespace

**Published Topics:**

.. list-table::
   :header-rows: 1
   :widths: 40 40

   * - Topic
     - Type
   * - livox/front/lidar
     - sensor_msgs/PointCloud2
   * - livox/rear/lidar
     - sensor_msgs/PointCloud2
   * - livox/front/imu
     - sensor_msgs/Imu
   * - livox/rear/imu
     - sensor_msgs/Imu
   * - scan
     - sensor_msgs/LaserScan

Depth Camera - RealSense D435i
------------------------------

The B2W can be equipped with Intel RealSense D435i depth cameras.

For RealSense documentation, see: https://github.com/IntelRealSense/realsense-ros

Pan-Tilt System (Dynamixel)
---------------------------

The ``b2_dynamixel`` package controls Dynamixel servos for pan-tilt mechanisms using Protocol 2.0.

**Hardware Setup:**

- **Supported Servos:** XM, XH, XC, XL430, XW series
- **Interface:** U2D2 USB adapter
- **Serial Port:** ``/dev/b2/dynamixel``
- **Baud Rate:** 57600

**Configuration:**

Configuration file: ``b2_dynamixel/config/dynamixel.yaml``

.. code-block:: yaml

   dynamixel_driver:
     ros__parameters:
       port: '/dev/b2/dynamixel'
       baudrate: 57600
       servo_ids: [0, 1]
       position_min: [1150, 230]
       position_max: [3200, 900]
       profile_velocity: 100
       profile_acceleration: 50
       publish_rate: 20.0
       position_topic_prefix: 'dynamixel/servo'
       feedback_topic: 'dynamixel/joint_states'

**Topics and Services:**

.. list-table::
   :header-rows: 1
   :widths: 35 25 30

   * - Topic/Service
     - Type
     - Description
   * - dynamixel/servo_0/command
     - Float64
     - Pan (1150-3200)
   * - dynamixel/servo_1/command
     - Float64
     - Tilt (230-900)
   * - dynamixel/joint_states
     - JointState
     - Positions (rad)
   * - dynamixel/reboot
     - Trigger
     - Clear errors

**Usage:**

.. code-block:: bash

   # Launch driver
   ros2 launch b2_dynamixel dynamixel.launch.py

   # Center pan servo (default: 2170)
   ros2 topic pub --once /dynamixel/servo_0/command \
     std_msgs/msg/Float64 "data: 2170"

   # Center tilt servo (default: 565)
   ros2 topic pub --once /dynamixel/servo_1/command \
     std_msgs/msg/Float64 "data: 565"

   # Read joint states
   ros2 topic echo /dynamixel/joint_states

   # Reboot servos (clear hardware errors)
   ros2 service call /dynamixel/reboot std_srvs/srv/Trigger

**Udev Rules:**

To create persistent device symlinks:

.. code-block:: bash

   echo 'SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", \
     ATTRS{idProduct}=="6014", SYMLINK+="b2/dynamixel", \
     MODE="0666"' | sudo tee /etc/udev/rules.d/99-dynamixel.rules
   sudo udevadm control --reload-rules
   sudo udevadm trigger

Z1 Robotic Arm
--------------

.. important::
   **EXPERIMENTAL:** The Z1 driver is under active development.

The ``b2_z1`` package provides a ROS 2 driver for the Unitree Z1 robotic arm.

**Quick Start:**

.. code-block:: bash

   # Launch the driver
   ros2 launch b2_z1 z1.launch.py

   # Enable the arm (required before sending commands)
   ros2 service call /b2_unit_001/z1/enable std_srvs/srv/Trigger

   # Send trajectory command
   ros2 topic pub --once /b2_unit_001/z1/joint_trajectory \
     trajectory_msgs/msg/JointTrajectory "{
       joint_names: ['joint1', 'joint2', 'joint3',
         'joint4', 'joint5', 'joint6', 'jointGripper'],
       points: [{
         positions: [0.0, 1.57, -1.57, 0.0, 0.0, 0.0, 0.0],
         time_from_start: {sec: 3, nanosec: 0}
       }]
     }"

   # Disable the arm
   ros2 service call /b2_unit_001/z1/disable std_srvs/srv/Trigger

**Topics and Services:**

.. list-table::
   :header-rows: 1
   :widths: 30 35 25

   * - Name
     - Type
     - Description
   * - z1/joint_states
     - sensor_msgs/JointState
     - Joint positions
   * - z1/joint_trajectory
     - trajectory_msgs/JointTrajectory
     - Commands
   * - z1/enable
     - std_srvs/Trigger
     - Enable arm
   * - z1/disable
     - std_srvs/Trigger
     - Disable arm

**URDF Integration:**

Enable Z1 in the robot description:

.. code-block:: bash

   export B2_Z1=1
   ros2 launch b2_description display.launch.py
