diff --git a/conf/airframes/examples/funjet.xml b/conf/airframes/examples/funjet.xml
index 151f823b26..2cb5c2318b 100644
--- a/conf/airframes/examples/funjet.xml
+++ b/conf/airframes/examples/funjet.xml
@@ -18,10 +18,10 @@
-
+
diff --git a/conf/airframes/examples/funjet_cam.xml b/conf/airframes/examples/funjet_cam.xml
index df4f9fd492..b91d524560 100644
--- a/conf/airframes/examples/funjet_cam.xml
+++ b/conf/airframes/examples/funjet_cam.xml
@@ -18,10 +18,10 @@
-
+
diff --git a/conf/airframes/twinjet_overo.xml b/conf/airframes/twinjet_overo.xml
index 21b49f2d4b..a5508b17cc 100644
--- a/conf/airframes/twinjet_overo.xml
+++ b/conf/airframes/twinjet_overo.xml
@@ -26,8 +26,8 @@
-
+
diff --git a/conf/firmwares/subsystems/shared/baro_board.makefile b/conf/firmwares/subsystems/shared/baro_board.makefile
index 37370e0510..62a49bc118 100644
--- a/conf/firmwares/subsystems/shared/baro_board.makefile
+++ b/conf/firmwares/subsystems/shared/baro_board.makefile
@@ -136,7 +136,7 @@ else ifeq ($(BOARD), hbmini)
BARO_BOARD_CFLAGS += -DUSE_I2C1
BARO_BOARD_SRCS += peripherals/bmp085.c
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c
-
+
# krooz baro
else ifeq ($(BOARD), krooz)
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c2
diff --git a/conf/flight_plans/MAV08_legs.kml b/conf/flight_plans/MAV08_legs.kml
old mode 100755
new mode 100644
diff --git a/conf/flight_plans/MAV08_no_fly_boundaries.kml b/conf/flight_plans/MAV08_no_fly_boundaries.kml
old mode 100755
new mode 100644
diff --git a/conf/flight_plans/flight_plan.dtd b/conf/flight_plans/flight_plan.dtd
index 33599ac043..68be3712bb 100644
--- a/conf/flight_plans/flight_plan.dtd
+++ b/conf/flight_plans/flight_plan.dtd
@@ -162,7 +162,9 @@ value CDATA #REQUIRED>
+until CDATA #IMPLIED
+loop CDATA #IMPLIED
+break CDATA #IMPLIED>
-
+
diff --git a/conf/modules/flight_benchmark.xml b/conf/modules/flight_benchmark.xml
index 939a955961..d561af883d 100644
--- a/conf/modules/flight_benchmark.xml
+++ b/conf/modules/flight_benchmark.xml
@@ -2,8 +2,32 @@
- Flight benchmark
+
+Flight benchmark.
+This module allows a quantitative assessment of the flight. It calculates the sum of squared error of the two-dimensional course (x / y), the altitude and true airspeed. The sum of squared error of the course and altitude were separated, because they are regulated separately, and so they dependent on various parameters. The module was written to optimize the control parameters and has already been used successfully.
+
+The measurement is not started until about the variable benchm_go is set to 1.
+
+The sum of squared error can by reseted by changing the boolean variable benchm_reset to zero (will turn back to 1 automatically after it has done the reset). This can also be used in a flight plan, which allows a flight plan with auto-reset. So it is possible to fly an oval or a eight figure with a sum of squared error that will be reseted at the very same point of the figure.
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -14,4 +38,3 @@
-
diff --git a/conf/modules/flight_time.xml b/conf/modules/flight_time.xml
index 46ab86b367..fd61468945 100644
--- a/conf/modules/flight_time.xml
+++ b/conf/modules/flight_time.xml
@@ -3,16 +3,23 @@
- Flight time calculator
+ Flight time calculator.
Allows to check how much time is left before the end of the competition.
+
+
+
+
+
+
+
-
+
-
\ No newline at end of file
+
diff --git a/conf/radios/dx6iCHNI.xml b/conf/radios/dx6iCHNI.xml
index 1f5b64055c..4057c95954 100644
--- a/conf/radios/dx6iCHNI.xml
+++ b/conf/radios/dx6iCHNI.xml
@@ -49,6 +49,6 @@ Note: a command may be reversed by exchanging min and max values
-
+
diff --git a/conf/radios/mx-16.xml b/conf/radios/mx-16.xml
old mode 100755
new mode 100644
diff --git a/conf/settings/modules/benchmark.xml b/conf/settings/modules/benchmark.xml
deleted file mode 100644
index 97f8a93ea1..0000000000
--- a/conf/settings/modules/benchmark.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/settings/modules/booz_dc.xml b/conf/settings/modules/booz_dc.xml
deleted file mode 100644
index 7f2df7b4d7..0000000000
--- a/conf/settings/modules/booz_dc.xml
+++ /dev/null
@@ -1,12 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/settings/modules/booz_drop.xml b/conf/settings/modules/booz_drop.xml
deleted file mode 100644
index 3cbedf95ab..0000000000
--- a/conf/settings/modules/booz_drop.xml
+++ /dev/null
@@ -1,14 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/settings/modules/flight_time.xml b/conf/settings/modules/flight_time.xml
deleted file mode 100644
index 312ec12ecc..0000000000
--- a/conf/settings/modules/flight_time.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
-
-
-
-
-
diff --git a/data/maps/Makefile b/data/maps/Makefile
index c7bac79afa..33c0de785c 100644
--- a/data/maps/Makefile
+++ b/data/maps/Makefile
@@ -6,10 +6,13 @@ Q=@
UNAME = $(shell uname -s)
ifeq ("$(UNAME)","Darwin")
MKTEMP = gmktemp
+ SED = gsed
else
MKTEMP = mktemp
+ SED = sed
endif
+
all: $(PAPARAZZI_HOME)/conf/maps.xml
clean:
@@ -28,16 +31,20 @@ $(DATADIR)/maps.google.com: $(DATADIR) FORCE
exit 1)
$(PAPARAZZI_HOME)/conf/maps.xml: $(DATADIR)/maps.google.com
- $(eval GOOGLE_VERSION := $(shell tr -s '[[:space:]]' '\n' < $(DATADIR)/maps.google.com | grep -E "http[s]?://khm[s]?[0-9]+.google.com/kh/v=[0-9]+.x26" | sed -e 's/.*http[s]\?:\/\/khm[s]\?[0-9]\+\.google\.com\/kh\/v=\([0-9]\+\)\\x26.*/\1/'))
+ $(eval GOOGLE_VERSION := $(shell tr -s '[[:space:]]' '\n' < $(DATADIR)/maps.google.com | grep -E "http[s]?://khm[s]?[0-9]+.google.com/kh/v=[0-9]+.x26" | $(SED) -r 's#.*http[s]?://khm[s]?[0-9]+.google.com/kh/v=##;s#.x26.*##'))
$(eval $@_TMP := $(shell $(MKTEMP)))
- @echo "Updated google maps version to $(GOOGLE_VERSION)"
- @echo "-----------------------------------------------"
- $(Q)echo "" > $($@_TMP)
- $(Q)echo "" >> $($@_TMP)
- $(Q)echo "" >> $($@_TMP)
- $(Q)echo "" >> $($@_TMP)
- $(Q)mv $($@_TMP) $@
- $(Q)chmod a+r $@
+ $(Q)if [ "$(GOOGLE_VERSION)" -eq "$(GOOGLE_VERSION)" ] 2>/dev/null ; then \
+ echo "Updated google maps version to $(GOOGLE_VERSION)" ; \
+ echo "-----------------------------------------------" ; \
+ echo "" > $($@_TMP) ; \
+ echo "" >> $($@_TMP) ; \
+ echo "" >> $($@_TMP) ; \
+ echo "" >> $($@_TMP) ; \
+ mv $($@_TMP) $@ ; \
+ chmod a+r $@ ; \
+ else \
+ echo "Extracted google maps version was not a valid number: $(GOOGLE_VERSION)" ; \
+ fi
FORCE:
.PHONY: all clean
diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c
index d23b63aef3..63940d1266 100644
--- a/sw/airborne/firmwares/rotorcraft/navigation.c
+++ b/sw/airborne/firmwares/rotorcraft/navigation.c
@@ -393,7 +393,7 @@ void nav_init_stage( void ) {
#include
void nav_periodic_task(void) {
- RunOnceEvery(16, { stage_time++; block_time++; });
+ RunOnceEvery(NAV_FREQ, { stage_time++; block_time++; });
dist2_to_wp = 0;
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
index 48ed47932f..4d296a1f21 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
@@ -30,6 +30,7 @@
#include "state.h"
#include "firmwares/rotorcraft/stabilization.h"
+#include "firmwares/rotorcraft/stabilization/stabilization_attitude.h"
#include "firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h"
#include "paparazzi.h"
diff --git a/sw/airborne/modules/digital_cam/catia/catia.c b/sw/airborne/modules/digital_cam/catia/catia.c
old mode 100755
new mode 100644
diff --git a/sw/airborne/modules/digital_cam/dc.c b/sw/airborne/modules/digital_cam/dc.c
index 8492e9a930..b6d20c6c6d 100644
--- a/sw/airborne/modules/digital_cam/dc.c
+++ b/sw/airborne/modules/digital_cam/dc.c
@@ -84,8 +84,14 @@ void dc_send_shot_position(void)
{
int16_t phi = DegOfRad(stateGetNedToBodyEulers_f()->phi*10.0f);
int16_t theta = DegOfRad(stateGetNedToBodyEulers_f()->theta*10.0f);
- float gps_z = ((float)gps.hmsl) / 1000.0f;
- int16_t course = (DegOfRad(gps.course)/((int32_t)1e6));
+ struct UtmCoor_f * utm = stateGetPositionUtm_f();
+ // east and north UTM position in cm
+ int32_t east = utm->east * 100;
+ int32_t north = utm->north * 100;
+ // course in decideg
+ int16_t course = DegOfRad(*stateGetHorizontalSpeedDir_f()) * 10;
+ // ground speed in cm/s
+ uint16_t speed = (*stateGetHorizontalSpeedNorm_f()) * 10;
int16_t photo_nr = -1;
if (dc_buffer < DC_IMAGE_BUFFER) {
@@ -96,14 +102,14 @@ void dc_send_shot_position(void)
DOWNLINK_SEND_DC_SHOT(DefaultChannel, DefaultDevice,
&photo_nr,
- &gps.utm_pos.east,
- &gps.utm_pos.north,
- &gps_z,
- &gps.utm_pos.zone,
+ &east,
+ &north,
+ &utm->alt,
+ &utm->zone,
&phi,
&theta,
&course,
- &gps.gspeed,
+ &speed,
&gps.tow);
}
#endif /* SENSOR_SYNC_SEND */
@@ -205,7 +211,7 @@ void dc_periodic_4Hz(void)
case DC_AUTOSHOOT_DISTANCE:
{
- uint32_t dist_to_100m_grid = (gps.utm_pos.north / 100) % 100;
+ uint32_t dist_to_100m_grid = (int32_t)stateGetPositionUtm_f()->north % 100;
if (dist_to_100m_grid < dc_autoshoot_meter_grid || 100 - dist_to_100m_grid < dc_autoshoot_meter_grid)
{
dc_send_command(DC_SHOOT);
diff --git a/sw/airborne/modules/digital_cam/dc.h b/sw/airborne/modules/digital_cam/dc.h
index 3b59a89da1..b575688b2b 100644
--- a/sw/airborne/modules/digital_cam/dc.h
+++ b/sw/airborne/modules/digital_cam/dc.h
@@ -187,7 +187,7 @@ extern uint8_t dc_circle(float interval, float start);
* If both 'x' and 'y' are DC_IGNORE the current position
* will be used as reference point.
*
- * @param interval minimum angle between shots in deg
+ * @param interval distance between shots in meters
* @param x x coordinate of reference point (or special DC_IGNORE)
* @param y y coordinate of reference point (or special DC_IGNORE)
* @return zero
diff --git a/sw/airborne/subsystems/gps.c b/sw/airborne/subsystems/gps.c
index 2e08ff4c15..d474e00e70 100644
--- a/sw/airborne/subsystems/gps.c
+++ b/sw/airborne/subsystems/gps.c
@@ -45,6 +45,22 @@ struct GpsTimeSync gps_time_sync;
#if PERIODIC_TELEMETRY
#include "subsystems/datalink/telemetry.h"
+static void send_svinfo(struct transport_tx *trans, struct device *dev, uint8_t svid) {
+ if (svid < GPS_NB_CHANNELS) {
+ pprz_msg_send_SVINFO(trans, dev, AC_ID, &svid,
+ &gps.svinfos[svid].svid, &gps.svinfos[svid].flags,
+ &gps.svinfos[svid].qi, &gps.svinfos[svid].cno,
+ &gps.svinfos[svid].elev, &gps.svinfos[svid].azim);
+ }
+}
+
+/** send SVINFO message if there is information for satellite with svid */
+static inline void send_svinfo_available(struct transport_tx *trans, struct device *dev, uint8_t svid) {
+ if (gps.svinfos[svid].cno > 0) {
+ send_svinfo(trans, dev, svid);
+ }
+}
+
static void send_gps(struct transport_tx *trans, struct device *dev) {
static uint8_t i;
int16_t climb = -gps.ned_vel.z;
@@ -53,13 +69,13 @@ static void send_gps(struct transport_tx *trans, struct device *dev) {
&gps.utm_pos.east, &gps.utm_pos.north,
&course, &gps.hmsl, &gps.gspeed, &climb,
&gps.week, &gps.tow, &gps.utm_pos.zone, &i);
+
+ // send SVINFO for all satellites while no GPS fix,
+ // after 3D fix, send avialable sats with lower rate
if ((gps.fix != GPS_FIX_3D) && (i >= gps.nb_channels)) i = 0;
if (i >= gps.nb_channels * 2) i = 0;
if (i < gps.nb_channels && ((gps.fix != GPS_FIX_3D) || (gps.svinfos[i].cno > 0))) {
- pprz_msg_send_SVINFO(trans, dev, AC_ID, &i,
- &gps.svinfos[i].svid, &gps.svinfos[i].flags,
- &gps.svinfos[i].qi, &gps.svinfos[i].cno,
- &gps.svinfos[i].elev, &gps.svinfos[i].azim);
+ send_svinfo(trans, dev, i);
}
i++;
}
@@ -77,12 +93,10 @@ static void send_gps_int(struct transport_tx *trans, struct device *dev) {
&gps.pdop,
&gps.num_sv,
&gps.fix);
+ // send SVINFO for available satellites that have new data
if (i == gps.nb_channels) i = 0;
- if (i < gps.nb_channels && gps.svinfos[i].cno > 0 && gps.svinfos[i].cno != last_cnos[i]) {
- pprz_msg_send_SVINFO(trans, dev, AC_ID, &i,
- &gps.svinfos[i].svid, &gps.svinfos[i].flags,
- &gps.svinfos[i].qi, &gps.svinfos[i].cno,
- &gps.svinfos[i].elev, &gps.svinfos[i].azim);
+ if (i < gps.nb_channels && gps.svinfos[i].cno != last_cnos[i]) {
+ send_svinfo_available(trans, dev, i);
last_cnos[i] = gps.svinfos[i].cno;
}
i++;
diff --git a/sw/airborne/subsystems/ins/ins_ardrone2.c b/sw/airborne/subsystems/ins/ins_ardrone2.c
index bf59909878..893bdbff7f 100644
--- a/sw/airborne/subsystems/ins/ins_ardrone2.c
+++ b/sw/airborne/subsystems/ins/ins_ardrone2.c
@@ -92,8 +92,12 @@ void ins_reset_altitude_ref( void ) {
void ins_propagate(float __attribute__((unused)) dt) {
/* untilt accels and speeds */
- float_rmat_transp_vmult(&ins_impl.ltp_accel, stateGetNedToBodyRMat_f(), &ahrs_impl.accel);
- float_rmat_transp_vmult(&ins_impl.ltp_speed, stateGetNedToBodyRMat_f(), &ahrs_impl.speed);
+ float_rmat_transp_vmult((struct FloatVect3*)&ins_impl.ltp_accel,
+ stateGetNedToBodyRMat_f(),
+ (struct FloatVect3*)&ahrs_impl.accel);
+ float_rmat_transp_vmult((struct FloatVect3*)&ins_impl.ltp_speed,
+ stateGetNedToBodyRMat_f(),
+ (struct FloatVect3*)&ahrs_impl.speed);
//Add g to the accelerations
ins_impl.ltp_accel.z += 9.81;
diff --git a/sw/simulator/nps/nps_flightgear.c b/sw/simulator/nps/nps_flightgear.c
index 0b84bd4b1a..d70d0260a2 100644
--- a/sw/simulator/nps/nps_flightgear.c
+++ b/sw/simulator/nps/nps_flightgear.c
@@ -82,7 +82,9 @@ void nps_flightgear_send() {
if (sendto(flightgear.socket, (char*)(&gui), sizeof(gui), 0,
- (struct sockaddr*)&flightgear.addr, sizeof(flightgear.addr)) == -1)
- printf("error sending\n");
+ (struct sockaddr*)&flightgear.addr, sizeof(flightgear.addr)) == -1) {
+ fprintf(stderr, "error sending to FlightGear\n");
+ fflush(stderr);
+ }
}
diff --git a/sw/simulator/sim.ml b/sw/simulator/sim.ml
index 44228c7e49..3c52fc4ff9 100644
--- a/sw/simulator/sim.ml
+++ b/sw/simulator/sim.ml
@@ -227,7 +227,7 @@ module Make(AircraftItl : AIRCRAFT_ITL) = struct
Aircraft.attitude_and_rates phi theta psi p q r in
(** Sending to Flight Gear *)
- let fg_task = fun socket buffer () ->
+ let fg_task = fun socket buffer sockaddr () ->
match !last_gps_state with
None -> ()
| Some s ->
@@ -239,9 +239,9 @@ module Make(AircraftItl : AIRCRAFT_ITL) = struct
fg_msg buffer lat lon alt phi theta psi;
(** for i = 0 to String.length buffer - 1 do fprintf stderr "%x " (Char.code buffer.[i]) done; fprintf stderr "\n"; **)
try
- ignore (Unix.send socket buffer 0 (String.length buffer) [])
+ ignore (Unix.sendto socket buffer 0 (String.length buffer) [] sockaddr)
with
- Unix.Unix_error (e,f,a) -> Printf.fprintf stderr "Error fg: %s (%s(%s))\n" (Unix.error_message e) f a
+ Unix.Unix_error (e,f,a) -> Printf.fprintf stderr "Error sending to FlightGear: %s (%s(%s))\n" (Unix.error_message e) f a; flush stderr
in
let set_pos = fun _ ->
@@ -271,11 +271,13 @@ module Make(AircraftItl : AIRCRAFT_ITL) = struct
try
let inet_addr = Unix.inet_addr_of_string !fg_client in
let socket = Unix.socket Unix.PF_INET Unix.SOCK_DGRAM 0 in
- Unix.connect socket (Unix.ADDR_INET (inet_addr, 5501));
+ (* Unix.connect socket (Unix.ADDR_INET (inet_addr, 5501)); *)
let buffer = String.create (fg_sizeof ()) in
- Stdlib.timer ~scale:time_scale fg_period (fg_task socket buffer)
+ let sockaddr = (Unix.ADDR_INET (inet_addr, 5501)) in
+ Stdlib.timer ~scale:time_scale fg_period (fg_task socket buffer sockaddr);
+ fprintf stdout "Sending to FlightGear at %s\n" !fg_client; flush stdout
with
- e -> fprintf stderr "Error while connecting to fg: %s" (Printexc.to_string e)
+ e -> fprintf stderr "Error setting up FlightGear viz: %s\n" (Printexc.to_string e); flush stderr
in
let take_off = fun () -> FlightModel.set_air_speed !state FM.nominal_airspeed in
diff --git a/sw/simulator/start_fg.sh b/sw/simulator/start_fg.sh
index 151de8460e..c27db3b70b 100755
--- a/sw/simulator/start_fg.sh
+++ b/sw/simulator/start_fg.sh
@@ -1,4 +1,4 @@
-#!/bin/bash
+#!/bin/sh
fgfs --fdm=null --native-gui=socket,in,30,,5501,udp --prop:/sim/model/path=Models/Aircraft/paparazzi/mikrokopter.xml
diff --git a/sw/tools/airframe_editor/paparazzi.py b/sw/tools/airframe_editor/paparazzi.py
index 772a6d8c4b..2227c4de07 100755
--- a/sw/tools/airframe_editor/paparazzi.py
+++ b/sw/tools/airframe_editor/paparazzi.py
@@ -80,16 +80,27 @@ def search(string):
if __name__ == '__main__':
- print("====HOME==== ", home_dir)
- print("----MODULES---- ", modules_dir)
- print(get_list_of_modules())
- for mod in get_list_of_modules():
- print(mod, " ---> ", get_module_information(mod))
- print("----FIRMWARES---- ", firmwares_dir)
- print(get_list_of_firmwares())
- for firm in get_list_of_firmwares():
- print(firm, " ---> ", get_list_of_subsystems(firm))
- print("shared", " ---> ", get_list_of_subsystems("shared"))
- print("----BOARDS---- ", firmwares_dir)
- print(get_list_of_boards())
+ print("\nPAPARAZZI\n=========\n\nContent listing of current branch\n")
+ print("\nBOARDS\n------\n")
+ boards = get_list_of_boards()
+ for b in boards:
+ print(" - ```" + b + "```" )
+ print("\nFIRMWARES - SUBSYSTEMS\n---------\n")
+ firmwares = get_list_of_firmwares()
+ firmwares.append("shared")
+ for f in firmwares:
+ print(" - " + f)
+ subsystems = get_list_of_subsystems(f)
+ for s in subsystems:
+ print(" - ```", s, "```")
+ print("\nMODULES\n-------\n")
+ modules = get_list_of_modules()
+ for m in modules:
+ info = get_module_information(m)
+ d = info.description
+ if ((d is None) or (len(d) == 0)):
+ d = " "
+ print(" - ```" + m + "``` " + d.split('\n', 1)[0])
+# for mod in get_list_of_modules():
+# print(mod, " ---> ", get_module_information(mod))
diff --git a/sw/tools/generators/gen_flight_plan.ml b/sw/tools/generators/gen_flight_plan.ml
index 4300d1d88d..4b1ff2f680 100644
--- a/sw/tools/generators/gen_flight_plan.ml
+++ b/sw/tools/generators/gen_flight_plan.ml
@@ -494,16 +494,38 @@ let rec print_stage = fun index_of_waypoints x ->
| "call" ->
stage ();
let statement = ExtXml.attrib x "fun" in
- lprintf "if (! (%s))\n" statement;
- lprintf " NextStageAndBreak();\n";
- begin
- try
- let c = parsed_attrib x "until" in
- lprintf "if (%s) NextStageAndBreak();\n" c
- with
- ExtXml.Error _ -> ()
- end;
- lprintf "break;\n"
+ (* by default, function is called while returning TRUE *)
+ (* otherwise, function is called once and returned value is ignored *)
+ let loop = String.uppercase (ExtXml.attrib_or_default x "loop" "TRUE") in
+ (* be default, go to next stage immediately *)
+ let break = String.uppercase (ExtXml.attrib_or_default x "break" "FALSE") in
+ begin match loop with
+ | "TRUE" ->
+ lprintf "if (! (%s)) {\n" statement;
+ begin match break with
+ | "TRUE" -> lprintf " NextStageAndBreak();\n";
+ | "FALSE" -> lprintf " NextStage();\n";
+ | _ -> failwith "FP: 'call' break attribute must be TRUE or FALSE";
+ end;
+ lprintf "} else {\n";
+ begin
+ try
+ let c = parsed_attrib x "until" in
+ lprintf " if (%s) NextStageAndBreak();\n" c
+ with
+ ExtXml.Error _ -> ()
+ end;
+ lprintf " break;\n";
+ lprintf "}\n"
+ | "FALSE" ->
+ lprintf "%s\n" statement;
+ begin match break with
+ | "TRUE" -> lprintf "NextStageAndBreak();\n";
+ | "FALSE" -> lprintf "NextStage();\n";
+ | _ -> failwith "FP: 'call' break attribute must be TRUE or FALSE";
+ end;
+ | _ -> failwith "FP: 'call' loop attribute must be TRUE or FALSE"
+ end
| "survey_rectangle" ->
let grid = parsed_attrib x "grid"
and wp1 = get_index_waypoint (ExtXml.attrib x "wp1") index_of_waypoints