Проект ArduCAM OSD [1] для передачи в MAX7456 отображаемой информации OSD (координаты GPS, высота, состояние батареи и т. д.) использует сообщения протокола MAVLink версии 1.0, передаваемые через UART [2]. По умолчанию библиотека MAVLink сгенерирована для использования полетного контроллера ArduPilotMega, для генерации использовался исходный XML-файл libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml. Если по какой-то причине вам необходимо поменять протокол для передачи информации OSD, библиотеку MAVLiink может понадобиться сгенерировать заново. Для регенерации кода библиотеки MAVLink используется скрипт libraries/GCS_MAVLink/generate.sh.
[Как генерировать библиотеки MAVLink для ArduCAM OSD]
Далее приведено пошаговое описание процесса в системе Ubuntu 24.04.2 LTS.
1. Для генерации библиотек у вас должен быть установлен пакет скриптов MAVLink. Это можно сделать, скачав репозиторий с официального сайта mavlink.io. Подробное описание установки см. в статье [1].
2. Убедитесь, что переменная окружения PATH содержит полный путь до каталога, где находится скрипт mavgen.py (это может быть путь наподобие $HOME/mavlink/pymavlink/tools, если вы установили пакет mavlink в домашнюю директорию пользователя. Я прописал у себя этот путь в файл .bashrc пользователя:
export PATH="$PATH:$HOME/mavlink/pymavlink/tools"
3. Перейдите в каталог libraries/GCS_MAVLink/ проекта ArduCAM OSD и выполните в нем скрипт generate.sh. Если скрипт не запускается, добавьте для него права на выполнение:
$ sudo chmod +x generate.sh
$ ./generate.sh
4. После успешного выполнения в каталоге libraries/GCS_MAVLink/include/mavlink/v1.0/ будут заново сгенерированы заголовочные файлы библиотеки MAVLink, которые вы можете использовать в других приложениях для отправки MAVLink-сообщений OSD в платку MICRO MinimOSD или MinimOSD (или любую другую, на которой работает проект ArduCAM OSD).
5. Не забудьте обновить содержимое каталога ~/Arduino/libraries/GCS_MAVLink (оттуда среда Arduino IDE берет библиотеки), там должна содержаться обновленная версия сгенерированной библиотеки MAVLink.
[Устранение ошибок генерации библиотек MAVLink]
1) generate.sh не запускается с ошибкой "cannot execute: required file not found". Причина в том, что generate.sh оформлен как текстовый файл Windows, у которых строки оканчиваются на 0x0D, 0x0A. Поможет утилита dos2unix.
2) Не проходит проверка файла common.xml:
Validating ~/Arduino/libraries/GCS_MAVLink/message_definitions/common.xml
ERROR: ~/Arduino/libraries/GCS_MAVLink/message_definitions/common.xml:1341:0:
ERROR:SCHEMASV:SCHEMAV_ELEMENT_CONTENT: Element 'field': This element is not expected.
Expected is one of ( deprecated, wip, description ).
~/Arduino/libraries/GCS_MAVLink/message_definitions/common.xml:1348:0:
ERROR:SCHEMASV:SCHEMAV_ELEMENT_CONTENT: Element 'field': This element is not expected.
Expected is one of ( deprecated, wip, description ). ...
.. и т. п.
Можно добавить в командную строку mavgen.py скрипта generate.sh опцию --no-validate, тогда файлы библиотеки MAVLink сгенерируются. Если же вы хотите сохранить возможность проверки, то понадобится более сложная процедура:
- В каталоге libraries/GCS_MAVLink/message_definitions замените файл common.xml, взяв копию из каталога установки MAVLink (см. папку ~/mavlink/message_definitions/v1.0/).
- Скопируйте в каталог libraries/GCS_MAVLink/message_definitions файл standard.xml, также взяв его из каталога установки MAVLink.
- Отредактируйте файл ardupilotmega.xml в каталоге libraries/GCS_MAVLink/message_definitions, удалив в нем перечисления MAV_MOUNT_MODE, MAV_CMD, MAV_CMD_DO_DIGICAM_CONTROL, MAV_CMD_DO_MOUNT_CONFIGURE, MAV_CMD_DO_MOUNT_CONTROL, FENCE_BREACH, FENCE_STATUS. Эти сообщения больше не нужны в файле ardupilotmega.xml, потому что дублируются в common.xml.
<?xml version='1.0'?><mavlink><include>common.xml</include><!-- note that APM specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
--><enums><!-- Camera Mount mode Enumeration --><!-- fenced mode enums --><enumname="FENCE_ACTION"><entryname="FENCE_ACTION_NONE"value="0"><description>Disable fenced mode</description></entry><entryname="FENCE_ACTION_GUIDED"value="1"><description>Switched to guided mode to return point (fence point 0)</description></entry></enum><!-- AP_Limits Enums --><enumname="LIMITS_STATE"><entryname="LIMITS_INIT"value="0"><description> pre-initialization</description></entry><entryname="LIMITS_DISABLED"value="1"><description> disabled</description></entry><entryname="LIMITS_ENABLED"value="2"><description> checking limits</description></entry><entryname="LIMITS_TRIGGERED"value="3"><description> a limit has been
breached</description></entry><entryname="LIMITS_RECOVERING"value="4"><description> taking action eg.
RTL</description></entry><entryname="LIMITS_RECOVERED"value="5"><description> we're no longer in breach of
a limit</description></entry></enum><!-- AP_Limits Modules - power of 2 (1,2,4,8,16,32 etc) so we can send as bitfield --><enumname="LIMIT_MODULE"><entryname="LIMIT_GPSLOCK"value="1"><description> pre-initialization</description></entry><entryname="LIMIT_GEOFENCE"value="2"><description> disabled</description></entry><entryname="LIMIT_ALTITUDE"value="4"><description> checking limits</description></entry></enum></enums><messages><messageid="150"name="SENSOR_OFFSETS"><description>Offsets and calibrations values for hardware
sensors. This makes it easier to debug the calibration process.</description><fieldtype="int16_t"name="mag_ofs_x">magnetometer X offset</field><fieldtype="int16_t"name="mag_ofs_y">magnetometer Y offset</field><fieldtype="int16_t"name="mag_ofs_z">magnetometer Z offset</field><fieldtype="float"name="mag_declination">magnetic declination (radians)</field><fieldtype="int32_t"name="raw_press">raw pressure from barometer</field><fieldtype="int32_t"name="raw_temp">raw temperature from barometer</field><fieldtype="float"name="gyro_cal_x">gyro X calibration</field><fieldtype="float"name="gyro_cal_y">gyro Y calibration</field><fieldtype="float"name="gyro_cal_z">gyro Z calibration</field><fieldtype="float"name="accel_cal_x">accel X calibration</field><fieldtype="float"name="accel_cal_y">accel Y calibration</field><fieldtype="float"name="accel_cal_z">accel Z calibration</field></message><messageid="151"name="SET_MAG_OFFSETS"><description>set the magnetometer offsets</description><fieldtype="uint8_t"name="target_system">System ID</field><fieldtype="uint8_t"name="target_component">Component ID</field><fieldtype="int16_t"name="mag_ofs_x">magnetometer X offset</field><fieldtype="int16_t"name="mag_ofs_y">magnetometer Y offset</field><fieldtype="int16_t"name="mag_ofs_z">magnetometer Z offset</field></message><messageid="152"name="MEMINFO"><description>state of APM memory</description><fieldtype="uint16_t"name="brkval">heap top</field><fieldtype="uint16_t"name="freemem">free memory</field></message><messageid="153"name="AP_ADC"><description>raw ADC output</description><fieldtype="uint16_t"name="adc1">ADC output 1</field><fieldtype="uint16_t"name="adc2">ADC output 2</field><fieldtype="uint16_t"name="adc3">ADC output 3</field><fieldtype="uint16_t"name="adc4">ADC output 4</field><fieldtype="uint16_t"name="adc5">ADC output 5</field><fieldtype="uint16_t"name="adc6">ADC output 6</field></message><!-- Camera Controller Messages --><messagename="DIGICAM_CONFIGURE"id="154"><description>Configure on-board Camera Control System.</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="mode"type="uint8_t">Mode enumeration from 1 to N //P,
TV, AV, M, Etc (0 means ignore)</field><fieldname="shutter_speed"type="uint16_t">Divisor number //e.g.
1000 means 1/1000 (0 means ignore)</field><fieldname="aperture"type="uint8_t">F stop number x 10 //e.g.
28 means 2.8 (0 means ignore)</field><fieldname="iso"type="uint8_t">ISO enumeration from 1 to N //e.g.
80, 100, 200, Etc (0 means ignore)</field><fieldname="exposure_type"type="uint8_t">Exposure type enumeration
from 1 to N (0 means ignore)</field><fieldname="command_id"type="uint8_t">Command Identity (incremental
loop: 0 to 255)//A command sent multiple times will be executed or
pooled just once</field><fieldname="engine_cut_off"type="uint8_t">Main engine cut-off time
before camera trigger in seconds/10 (0 means no cut-off)</field><fieldname="extra_param"type="uint8_t">Extra parameters enumeration
(0 means ignore)</field><fieldname="extra_value"type="float">Correspondent value to given
extra_param</field></message><messagename="DIGICAM_CONTROL"id="155"><description>Control on-board Camera Control System to take shots.</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="session"type="uint8_t">0: stop, 1: start or keep it up
//Session control e.g. show/hide lens</field><fieldname="zoom_pos"type="uint8_t">1 to N //Zoom's absolute position
(0 means ignore)</field><fieldname="zoom_step"type="int8_t">-100 to 100 //Zooming step value
to offset zoom from the current position</field><fieldname="focus_lock"type="uint8_t">0: unlock focus or keep unlocked,
1: lock focus or keep locked, 3: re-lock focus</field><fieldname="shot"type="uint8_t">0: ignore, 1: shot or start filming</field><fieldname="command_id"type="uint8_t">Command Identity (incremental loop:
0 to 255)//A command sent multiple times will be executed or pooled just
once</field><fieldname="extra_param"type="uint8_t">Extra parameters enumeration
(0 means ignore)</field><fieldname="extra_value"type="float">Correspondent value to given
extra_param</field></message><!-- Camera Mount Messages --><messagename="MOUNT_CONFIGURE"id="156"><description>Message to configure a camera mount, directional antenna,
etc.</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="mount_mode"type="uint8_t">mount operating mode (see
MAV_MOUNT_MODE enum)</field><fieldname="stab_roll"type="uint8_t">(1 = yes, 0 = no)</field><fieldname="stab_pitch"type="uint8_t">(1 = yes, 0 = no)</field><fieldname="stab_yaw"type="uint8_t">(1 = yes, 0 = no)</field></message><messagename="MOUNT_CONTROL"id="157"><description>Message to control a camera mount, directional antenna,
etc.</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="input_a"type="int32_t">pitch(deg*100) or lat, depending
on mount mode</field><fieldname="input_b"type="int32_t">roll(deg*100) or lon depending
on mount mode</field><fieldname="input_c"type="int32_t">yaw(deg*100) or alt (in cm)
depending on mount mode</field><fieldname="save_position"type="uint8_t">if "1" it will save current
trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field></message><messagename="MOUNT_STATUS"id="158"><description>Message with some status from APM to GCS about camera or
antenna mount</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="pointing_a"type="int32_t">pitch(deg*100) or lat,
depending on mount mode</field><fieldname="pointing_b"type="int32_t">roll(deg*100) or lon depending
on mount mode</field><fieldname="pointing_c"type="int32_t">yaw(deg*100) or alt (in cm)
depending on mount mode</field></message><!-- geo-fence messages --><messagename="FENCE_POINT"id="160"><description>A fence point. Used to set a point when from
GCS -> MAV. Also used to return a point from MAV -> GCS</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="idx"type="uint8_t">point index (first point is 1, 0 is
for return point)</field><fieldname="count"type="uint8_t">total number of points (for sanity
checking)</field><fieldname="lat"type="float">Latitude of point</field><fieldname="lng"type="float">Longitude of point</field></message><messagename="FENCE_FETCH_POINT"id="161"><description>Request a current fence point from MAV</description><fieldname="target_system"type="uint8_t">System ID</field><fieldname="target_component"type="uint8_t">Component ID</field><fieldname="idx"type="uint8_t">point index (first point is 1,
0 is for return point)</field></message><messagename="AHRS"id="163"><description>Status of DCM attitude estimator</description><fieldtype="float"name="omegaIx">X gyro drift estimate rad/s</field><fieldtype="float"name="omegaIy">Y gyro drift estimate rad/s</field><fieldtype="float"name="omegaIz">Z gyro drift estimate rad/s</field><fieldtype="float"name="accel_weight">average accel_weight</field><fieldtype="float"name="renorm_val">average renormalisation value</field><fieldtype="float"name="error_rp">average error_roll_pitch value</field><fieldtype="float"name="error_yaw">average error_yaw value</field></message><messagename="SIMSTATE"id="164"><description>Status of simulation environment, if used</description><fieldtype="float"name="roll">Roll angle (rad)</field><fieldtype="float"name="pitch">Pitch angle (rad)</field><fieldtype="float"name="yaw">Yaw angle (rad)</field><fieldtype="float"name="xacc">X acceleration m/s/s</field><fieldtype="float"name="yacc">Y acceleration m/s/s</field><fieldtype="float"name="zacc">Z acceleration m/s/s</field><fieldtype="float"name="xgyro">Angular speed around X axis rad/s</field><fieldtype="float"name="ygyro">Angular speed around Y axis rad/s</field><fieldtype="float"name="zgyro">Angular speed around Z axis rad/s</field><fieldtype="float"name="lat">Latitude in degrees</field><fieldtype="float"name="lng">Longitude in degrees</field></message><messagename="HWSTATUS"id="165"><description>Status of key hardware</description><fieldtype="uint16_t"name="Vcc">board voltage (mV)</field><fieldtype="uint8_t"name="I2Cerr">I2C error count</field></message><messagename="RADIO"id="166"><description>Status generated by radio</description><fieldtype="uint8_t"name="rssi">local signal strength</field><fieldtype="uint8_t"name="remrssi">remote signal strength</field><fieldtype="uint8_t"name="txbuf">how full the tx buffer is as
a percentage</field><fieldtype="uint8_t"name="noise">background noise level</field><fieldtype="uint8_t"name="remnoise">remote background noise level</field><fieldtype="uint16_t"name="rxerrors">receive errors</field><fieldtype="uint16_t"name="fixed">count of error corrected packets</field></message><!-- AP_Limits status --><messagename="LIMITS_STATUS"id="167"><description>Status of AP_Limits. Sent in extended
status stream when AP_Limits is enabled</description><fieldname="limits_state"type="uint8_t">state of AP_Limits, (see enum
LimitState, LIMITS_STATE)</field><fieldname="last_trigger"type="uint32_t">time of last breach in
milliseconds since boot</field><fieldname="last_action"type="uint32_t">time of last recovery action
in milliseconds since boot</field><fieldname="last_recovery"type="uint32_t">time of last successful recovery
in milliseconds since boot</field><fieldname="last_clear"type="uint32_t">time of last all-clear in
milliseconds since boot</field><fieldname="breach_count"type="uint16_t">number of fence breaches</field><fieldname="mods_enabled"type="uint8_t">AP_Limit_Module bitfield of
enabled modules, (see enum moduleid or LIMIT_MODULE)</field><fieldname="mods_required"type="uint8_t">AP_Limit_Module bitfield of
required modules, (see enum moduleid or LIMIT_MODULE)</field><fieldname="mods_triggered"type="uint8_t">AP_Limit_Module bitfield of
triggered modules, (see enum moduleid or LIMIT_MODULE)</field></message><messagename="WIND"id="168"><description>Wind estimation</description><fieldtype="float"name="direction">wind direction (degrees)</field><fieldtype="float"name="speed">wind speed in ground plane (m/s)</field><fieldtype="float"name="speed_z">vertical wind speed (m/s)</field></message></messages></mavlink>