ArduCAM OSD: регенерация библиотеки MAVLink |
![]() |
Добавил(а) microsin |
Проект 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 --> <enum name="FENCE_ACTION"> <entry name="FENCE_ACTION_NONE" value="0"> <description>Disable fenced mode</description> </entry> <entry name="FENCE_ACTION_GUIDED" value="1"> <description>Switched to guided mode to return point (fence point 0)</description> </entry> </enum> <!-- AP_Limits Enums --> <enum name="LIMITS_STATE"> <entry name="LIMITS_INIT" value="0"> <description> pre-initialization</description></entry> <entry name="LIMITS_DISABLED" value="1"> <description> disabled</description></entry> <entry name="LIMITS_ENABLED" value="2"> <description> checking limits</description></entry> <entry name="LIMITS_TRIGGERED" value="3"> <description> a limit has been breached</description></entry> <entry name="LIMITS_RECOVERING" value="4"> <description> taking action eg. RTL</description></entry> <entry name="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 --> <enum name="LIMIT_MODULE"> <entry name="LIMIT_GPSLOCK" value="1"> <description> pre-initialization</description></entry> <entry name="LIMIT_GEOFENCE" value="2"> <description> disabled</description></entry> <entry name="LIMIT_ALTITUDE" value="4"> <description> checking limits</description></entry> </enum> </enums> <messages> <message id="150" name="SENSOR_OFFSETS"> <description>Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.</description> <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> <field type="float" name="mag_declination">magnetic declination (radians)</field> <field type="int32_t" name="raw_press">raw pressure from barometer</field> <field type="int32_t" name="raw_temp">raw temperature from barometer</field> <field type="float" name="gyro_cal_x">gyro X calibration</field> <field type="float" name="gyro_cal_y">gyro Y calibration</field> <field type="float" name="gyro_cal_z">gyro Z calibration</field> <field type="float" name="accel_cal_x">accel X calibration</field> <field type="float" name="accel_cal_y">accel Y calibration</field> <field type="float" name="accel_cal_z">accel Z calibration</field> </message> <message id="151" name="SET_MAG_OFFSETS"> <description>set the magnetometer offsets</description> <field type="uint8_t" name="target_system">System ID</field> <field type="uint8_t" name="target_component">Component ID</field> <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> </message> <message id="152" name="MEMINFO"> <description>state of APM memory</description> <field type="uint16_t" name="brkval">heap top</field> <field type="uint16_t" name="freemem">free memory</field> </message> <message id="153" name="AP_ADC"> <description>raw ADC output</description> <field type="uint16_t" name="adc1">ADC output 1</field> <field type="uint16_t" name="adc2">ADC output 2</field> <field type="uint16_t" name="adc3">ADC output 3</field> <field type="uint16_t" name="adc4">ADC output 4</field> <field type="uint16_t" name="adc5">ADC output 5</field> <field type="uint16_t" name="adc6">ADC output 6</field> </message> <!-- Camera Controller Messages --> <message name="DIGICAM_CONFIGURE" id="154"> <description>Configure on-board Camera Control System.</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field> <field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field> <field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field> <field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field> <field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field> <field name="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> <field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field> <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> <field name="extra_value" type="float">Correspondent value to given extra_param</field> </message> <message name="DIGICAM_CONTROL" id="155"> <description>Control on-board Camera Control System to take shots.</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field> <field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field> <field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field> <field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field> <field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field> <field name="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> <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> <field name="extra_value" type="float">Correspondent value to given extra_param</field> </message> <!-- Camera Mount Messages --> <message name="MOUNT_CONFIGURE" id="156"> <description>Message to configure a camera mount, directional antenna, etc.</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field> <field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field> <field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field> <field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field> </message> <message name="MOUNT_CONTROL" id="157"> <description>Message to control a camera mount, directional antenna, etc.</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> <field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> <field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> <field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field> </message> <message name="MOUNT_STATUS" id="158"> <description>Message with some status from APM to GCS about camera or antenna mount</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> <field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> <field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> </message> <!-- geo-fence messages --> <message name="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> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> <field name="count" type="uint8_t">total number of points (for sanity checking)</field> <field name="lat" type="float">Latitude of point</field> <field name="lng" type="float">Longitude of point</field> </message> <message name="FENCE_FETCH_POINT" id="161"> <description>Request a current fence point from MAV</description> <field name="target_system" type="uint8_t">System ID</field> <field name="target_component" type="uint8_t">Component ID</field> <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> </message> <message name="AHRS" id="163"> <description>Status of DCM attitude estimator</description> <field type="float" name="omegaIx">X gyro drift estimate rad/s</field> <field type="float" name="omegaIy">Y gyro drift estimate rad/s</field> <field type="float" name="omegaIz">Z gyro drift estimate rad/s</field> <field type="float" name="accel_weight">average accel_weight</field> <field type="float" name="renorm_val">average renormalisation value</field> <field type="float" name="error_rp">average error_roll_pitch value</field> <field type="float" name="error_yaw">average error_yaw value</field> </message> <message name="SIMSTATE" id="164"> <description>Status of simulation environment, if used</description> <field type="float" name="roll">Roll angle (rad)</field> <field type="float" name="pitch">Pitch angle (rad)</field> <field type="float" name="yaw">Yaw angle (rad)</field> <field type="float" name="xacc">X acceleration m/s/s</field> <field type="float" name="yacc">Y acceleration m/s/s</field> <field type="float" name="zacc">Z acceleration m/s/s</field> <field type="float" name="xgyro">Angular speed around X axis rad/s</field> <field type="float" name="ygyro">Angular speed around Y axis rad/s</field> <field type="float" name="zgyro">Angular speed around Z axis rad/s</field> <field type="float" name="lat">Latitude in degrees</field> <field type="float" name="lng">Longitude in degrees</field> </message> <message name="HWSTATUS" id="165"> <description>Status of key hardware</description> <field type="uint16_t" name="Vcc">board voltage (mV)</field> <field type="uint8_t" name="I2Cerr">I2C error count</field> </message> <message name="RADIO" id="166"> <description>Status generated by radio</description> <field type="uint8_t" name="rssi">local signal strength</field> <field type="uint8_t" name="remrssi">remote signal strength</field> <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field> <field type="uint8_t" name="noise">background noise level</field> <field type="uint8_t" name="remnoise">remote background noise level</field> <field type="uint16_t" name="rxerrors">receive errors</field> <field type="uint16_t" name="fixed">count of error corrected packets</field> </message> <!-- AP_Limits status --> <message name="LIMITS_STATUS" id="167"> <description>Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled</description> <field name="limits_state" type="uint8_t">state of AP_Limits, (see enum LimitState, LIMITS_STATE)</field> <field name="last_trigger" type="uint32_t">time of last breach in milliseconds since boot</field> <field name="last_action" type="uint32_t">time of last recovery action in milliseconds since boot</field> <field name="last_recovery" type="uint32_t">time of last successful recovery in milliseconds since boot</field> <field name="last_clear" type="uint32_t">time of last all-clear in milliseconds since boot</field> <field name="breach_count" type="uint16_t">number of fence breaches</field> <field name="mods_enabled" type="uint8_t">AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)</field> <field name="mods_required" type="uint8_t">AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)</field> <field name="mods_triggered" type="uint8_t">AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)</field> </message> <message name="WIND" id="168"> <description>Wind estimation</description> <field type="float" name="direction">wind direction (degrees)</field> <field type="float" name="speed">wind speed in ground plane (m/s)</field> <field type="float" name="speed_z">vertical wind speed (m/s)</field> </message> </messages> </mavlink> - Исправьте файл libraries/GCS_MAVLink/GCS_MAVLink.cpp: //mavlink_system_t mavlink_system = {12,1,0,0}; После запуска скрипта generate.sh не забудьте обновить этими исправлениями каталог ~/Arduino/libraries/GCS_MAVLink/. [Ссылки] 1. ArduCAM OSD Project.
|