Настройка launch-файлов

Настройка расположения камеры

Для работы с основной камерой необходимо убедиться что она включена в файле ~/catkin_ws/src/clover/clover/launch/clover.launch:

<arg name="main_camera" default="true"/>

Расположение и ориентация камеры задается в файле ~/catkin_ws/src/clover/clover/launch/main_camera.launch:

<arg name="direction_z" default="down"/> <!-- direction the camera points: down, up -->
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->

Для того, чтобы задать ориентацию, необходимо установить:

  • направление обзора камеры direction_z: вниз (down) или вверх (up);

  • направление, в которое указывает шлейф камеры direction_y: назад (backward) или вперед (forward).

Настройка Aruco и Optical Flow

Аргумент aruco в файле ~/catkin_ws/src/clover/clover/launch/clover.launch должен быть в значении true:

<arg name="aruco" default="true"/>

Для включения распознавания отдельных маркеров и карт маркеров аргументы aruco_detect и aruco_map в файле ~/catkin_ws/src/clover/clover/launch/aruco.launch должны быть в значении true:

<arg name="aruco_detect" default="true"/>
<arg name="aruco_map" default="true"/>

Для включения передачи координат в полётный контроллер по механизму VPE, аргумента aruco_vpe должен быть в значении true:

<arg name="aruco_vpe" default="true"/>

Для правильной работы в этом же файле также должны быть выставлены аргументы:

<arg name="placement" default="floor"/> <!-- расположение маркеров, см. далее -->
<arg name="length" default="0.33"/>     <!-- размер маркеров в метрах (не включая белую рамку) -->

Значение аргумента placement следует выставлять следующим образом:

  • если все маркеры наклеены на полу (земле), выставить значение floor;

  • если все маркеры наклеены на потолке, выставить значение ceiling;

  • в противном случае удалить строку с параметром.

Если некоторые маркеры имеют размер, отличный значения length, их размер может быть переопределен с помощью параметра length_override ноды aruco_detect:

<param name="length_override/3" value="0.1"/>    <!-- маркер c id 3 имеет размер 10 см -->
<param name="length_override/17" value="0.25"/>  <!-- маркер c id 17 имеет размер 25 см -->

Включите Optical Flow в файле ~/catkin_ws/src/clover/clover/launch/clover.launch:

<arg name="optical_flow" default="true"/>

Для работы Optical Flow необходим подключенный и настроенный лазерный дальномер.

Отредактируйте файл ~/catkin_ws/src/clover/clover/launch/clover.launch так, чтобы драйвер VL53L1X был включен:

<arg name="rangefinder_vl53l1x" default="true"/>

По умолчания драйвер дальномера передает данные в Pixhawk (через топик /rangefinder/range). Для просмотра данных из топика используйте команду:

rostopic echo /rangefinder/range

Настройка карты маркеров

Карта загружается из текстового файла, каждая строка которого имеет следующий формат:

id_маркера размер_маркера x y z угол_z угол_y угол_x

Где угол_N – это угол поворота маркера вокруг оси N в радианах.

Файлы карт располагаются в каталоге ~/catkin_ws/src/clover/aruco_pose/map. Название файла с картой задается в аргументе map:

<arg name="map" default="map.txt"/>

Смотрите примеры карт маркеров в вышеуказанном каталоге.

Файл карты может быть сгенерирован с помощью инструмента genmap.py:

rosrun aruco_pose genmap.py length x y dist_x dist_y first -o test_map.txt

Где length – размер маркера, x – количество маркеров по оси x, y - количество маркеров по оси y, dist_x – расстояние между центрами маркеров по оси x, y – расстояние между центрами маркеров по оси y, first – ID первого (левого нижнего) маркера, test_map.txt – название файла с картой. Дополнительный ключ --bottom-left позволяет нумеровать маркеры с левого нижнего угла.

Пример:

rosrun aruco_pose genmap.py 0.33 2 4 1 1 0 -o test_map.txt

Дополнительную информацию по утилите можно получить по ключу -h: rosrun aruco_pose genmap.py -h.

После обновления карты маркеров следует перезагрузить RPi.

Для контроля карты, по которой в данный момент коптер осуществляет навигацию, можно просмотреть содержимое топика /aruco_map/image. Через браузер его можно просмотреть при помощи web_video_server по ссылке http://192.168.11.1:8080/snapshot?topic=/aruco_map/image .

Настройка led-ленты

  1. Для работы с лентой подключите ее к питанию +5v – 5v, земле GND – GND и сигнальному порту DIN – GPIO21. Обратитесь к инструкции по сборке для подробностей.

  2. Включите поддержку LED-ленты в файле ~/catkin_ws/src/clover/clover/launch/clover.launch:

 <arg name="led" default="true"/>
  1. Настройте параметры подключения ленты ws281x в файле ~/catkin_ws/src/clover/clover/launch/led.launch. Необходимо ввести верное количество светодиодов в ленте и GPIO-пин, использованный для подключения (если он отличается от GPIO21):

 <arg name="led_count" default="58"/> <!-- количество светодиодов в ленте -->
 <arg name="gpio_pin" default="21"/> <!-- GPIO-пин для подключения -->

Last updated