mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-09 22:49:53 +08:00
dd7b07ab60
- register mission status message for telemetry, so it can be used on extra link with companion computer - add altitude proximity option to check alt on waypoints, not only 2D position - add documentation to XML file
48 lines
2.4 KiB
XML
48 lines
2.4 KiB
XML
<!DOCTYPE module SYSTEM "module.dtd">
|
|
|
|
<module name="mission_common" dir="mission" task="control">
|
|
<doc>
|
|
<description>
|
|
Common interface for mission control.
|
|
This module parse datalink commands for basic navigation routines
|
|
and store them in a queue.
|
|
</description>
|
|
<section name="MISSION" prefix="MISSION_">
|
|
<define name="ELEMENT_NB" value="20" description="maximum number of elements in the mission queue"/>
|
|
<define name="REGISTER_NB" value="6" description="maximum number of custom elemets to register"/>
|
|
<define name="CHECK_UNIQUE_ID" value="TRUE|FALSE" description="check before inserting that all elements ID are unique in the queue (default: TRUE)"/>
|
|
<define name="ALT_PROXIMITY" value="distance" unit="m" description="if defined, enforce a vertical proximity to validate the target points (default: undefined)"/>
|
|
<define name="WAIT_TIMEOUT" value="time" unit="s" description="time in waiting pattern when queue is empty before ending the mission (default: fixedwing=120, rotorcraft=30)"/>
|
|
</section>
|
|
</doc>
|
|
<header>
|
|
<file name="mission_common.h"/>
|
|
</header>
|
|
<init fun="mission_init()"/>
|
|
<periodic fun="mission_status_report()" freq="2" autorun="TRUE"/>
|
|
|
|
<datalink message="MISSION_GOTO_WP" fun="mission_parse_GOTO_WP(buf)"/>
|
|
<datalink message="MISSION_GOTO_WP_LLA" fun="mission_parse_GOTO_WP_LLA(buf)"/>
|
|
<datalink message="MISSION_CIRCLE" fun="mission_parse_CIRCLE(buf)"/>
|
|
<datalink message="MISSION_CIRCLE_LLA" fun="mission_parse_CIRCLE_LLA(buf)"/>
|
|
<datalink message="MISSION_SEGMENT" fun="mission_parse_SEGMENT(buf)"/>
|
|
<datalink message="MISSION_SEGMENT_LLA" fun="mission_parse_SEGMENT_LLA(buf)"/>
|
|
<datalink message="MISSION_PATH" fun="mission_parse_PATH(buf)"/>
|
|
<datalink message="MISSION_PATH_LLA" fun="mission_parse_PATH_LLA(buf)"/>
|
|
<datalink message="MISSION_CUSTOM" fun="mission_parse_CUSTOM(buf)"/>
|
|
<datalink message="MISSION_UPDATE" fun="mission_parse_UPDATE(buf)"/>
|
|
<datalink message="GOTO_MISSION" fun="mission_parse_GOTO_MISSION(buf)"/>
|
|
<datalink message="NEXT_MISSION" fun="mission_parse_NEXT_MISSION(buf)"/>
|
|
<datalink message="END_MISSION" fun="mission_parse_END_MISSION(buf)"/>
|
|
|
|
<makefile>
|
|
<define name="USE_MISSION"/>
|
|
<file name="mission_common.c"/>
|
|
<test firmware="fixedwing">
|
|
<define name="DOWNLINK_TRANSPORT" value="pprz_tp"/>
|
|
<define name="DOWNLINK_DEVICE" value="uart0"/>
|
|
<define name="USE_UART0"/>
|
|
</test>
|
|
</makefile>
|
|
</module>
|