mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-24 22:05:58 +08:00
add a "module" attribute in telemetry definition
a PERIODIC_SEND_XXX is generated only if the corresponding module is loaded
This commit is contained in:
+4
-4
@@ -96,9 +96,9 @@ ifeq ($(MAKECMDGOALS),all_ac_h)
|
||||
-include $(MAKEFILE_AC)
|
||||
endif
|
||||
|
||||
$(PERIODIC_H) : $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TELEMETRY) $(MAKEFILE_AC)
|
||||
$(PERIODIC_H) : $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TELEMETRY) $(MAKEFILE_AC)
|
||||
@echo BUILD $@
|
||||
$(Q)$(TOOLS)/gen_periodic.out $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(PERIODIC_FREQ) > $@
|
||||
$(Q)$(TOOLS)/gen_periodic.out $(CONF)/$(AIRFRAME_XML) $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(PERIODIC_FREQ) > $@
|
||||
$(Q)chmod a+r $@
|
||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)
|
||||
$(Q)cp $(CONF)/$(TELEMETRY) $(AIRCRAFT_CONF_DIR)/telemetry
|
||||
@@ -160,10 +160,10 @@ tiny_bl.upload:
|
||||
lpc21isp -control $(AIRBORNE)/arm7/test/bootloader/bl.hex $(BOOTLOADER_DEVICE) 38400 12000
|
||||
|
||||
jsbsim jsbsim.compile: ac_h
|
||||
cd $(AIRBORNE); $(MAKE) TARGET=jsbsim ARCHI=jsbsim all
|
||||
cd $(AIRBORNE); $(MAKE) TARGET=jsbsim ARCHI=jsbsim ARCH=jsbsim all
|
||||
|
||||
sim: ac_h
|
||||
cd $(AIRBORNE); $(MAKE) TARGET=sim ARCHI=sim all
|
||||
cd $(AIRBORNE); $(MAKE) TARGET=sim ARCHI=sim ARCH=sim all
|
||||
|
||||
# Rules for backward compatibility (old guys are used to !)
|
||||
fbw : fbw.compile
|
||||
|
||||
@@ -15,4 +15,5 @@
|
||||
name CDATA #REQUIRED
|
||||
period CDATA #REQUIRED
|
||||
phase CDATA #IMPLIED
|
||||
module CDATA #IMPLIED
|
||||
>
|
||||
|
||||
+69
-50
@@ -26,6 +26,11 @@
|
||||
|
||||
open Printf
|
||||
|
||||
let (//) = Filename.concat
|
||||
|
||||
let paparazzi_conf = Env.paparazzi_home // "conf"
|
||||
let modules_dir = paparazzi_conf // "modules"
|
||||
|
||||
|
||||
let margin = ref 0
|
||||
let step = 2
|
||||
@@ -48,7 +53,7 @@ let remove_dup = fun l ->
|
||||
loop (List.sort compare l)
|
||||
|
||||
|
||||
let output_modes = fun avr_h process_name channel_name modes freq ->
|
||||
let output_modes = fun avr_h process_name channel_name modes freq modules ->
|
||||
let min_period = 1./.float freq in
|
||||
let max_period = 65536. /. float freq in
|
||||
(** For each mode in this process *)
|
||||
@@ -58,24 +63,23 @@ let output_modes = fun avr_h process_name channel_name modes freq ->
|
||||
lprintf avr_h "if (telemetry_mode_%s_%s == TELEMETRY_MODE_%s_%s_%s) {\\\n" process_name channel_name process_name channel_name mode_name;
|
||||
right ();
|
||||
|
||||
(** Filter message list to remove messages linked to unloaded modules *)
|
||||
let filtered_msg = List.filter (fun msg ->
|
||||
try let att = Xml.attrib msg "module" in List.exists (fun name -> String.compare name att = 0) modules with _ -> true
|
||||
) (Xml.children mode) in
|
||||
(** Computes the required modulos *)
|
||||
let messages =
|
||||
List.map
|
||||
(fun x ->
|
||||
let p = float_of_string (ExtXml.attrib x "period") in
|
||||
if p < min_period || p > max_period then
|
||||
fprintf stderr "Warning: period is bound between %.3fs and %.3fs for message %s\n%!" min_period max_period (ExtXml.attrib x "name");
|
||||
(x, min 65535 (max 1 (int_of_float (p*.float_of_int freq)))))
|
||||
(Xml.children mode)
|
||||
in
|
||||
let messages = List.map (fun x ->
|
||||
let p = float_of_string (ExtXml.attrib x "period") in
|
||||
if p < min_period || p > max_period then
|
||||
fprintf stderr "Warning: period is bound between %.3fs and %.3fs for message %s\n%!" min_period max_period (ExtXml.attrib x "name");
|
||||
(x, min 65535 (max 1 (int_of_float (p*.float_of_int freq))))
|
||||
) filtered_msg in
|
||||
let modulos = remove_dup (List.map snd messages) in
|
||||
List.iter
|
||||
(fun m ->
|
||||
let v = sprintf "i%d" m in
|
||||
let _type = if m >= 256 then "uint16_t" else "uint8_t" in
|
||||
lprintf avr_h "static %s %s = 0; %s++; if (%s>=%d) %s=0;\\\n" _type v v v m v;
|
||||
)
|
||||
modulos;
|
||||
List.iter (fun m ->
|
||||
let v = sprintf "i%d" m in
|
||||
let _type = if m >= 256 then "uint16_t" else "uint8_t" in
|
||||
lprintf avr_h "static %s %s = 0; %s++; if (%s>=%d) %s=0;\\\n" _type v v v m v;
|
||||
) modulos;
|
||||
|
||||
(** For each message in this mode *)
|
||||
let messages = List.sort (fun (_,p) (_,p') -> compare p p') messages in
|
||||
@@ -83,43 +87,58 @@ let output_modes = fun avr_h process_name channel_name modes freq ->
|
||||
let phase = ref 0 in
|
||||
let l = ref [] in
|
||||
List.iter
|
||||
(fun (message, p) ->
|
||||
let message_name = ExtXml.attrib message "name" in
|
||||
i := !i mod p;
|
||||
(* if phase attribute is present, use it, otherwise shedule at 10Hz *)
|
||||
let message_phase = try int_of_float (float_of_string (ExtXml.attrib message "phase")*.float_of_int freq) with _ -> !i in
|
||||
phase := message_phase;
|
||||
let else_ = if List.mem_assoc p !l && not (List.mem (p, !phase) !l) then "else " else "" in
|
||||
lprintf avr_h "%sif (i%d == %d) {\\\n" else_ p !phase;
|
||||
l := (p, !phase) :: !l;
|
||||
i := !i + freq/10;
|
||||
right ();
|
||||
lprintf avr_h "PERIODIC_SEND_%s(%s);\\\n" message_name channel_name;
|
||||
left ();
|
||||
lprintf avr_h "} \\\n"
|
||||
)
|
||||
messages;
|
||||
(fun (message, p) ->
|
||||
let message_name = ExtXml.attrib message "name" in
|
||||
i := !i mod p;
|
||||
(* if phase attribute is present, use it, otherwise shedule at 10Hz *)
|
||||
let message_phase = try int_of_float (float_of_string (ExtXml.attrib message "phase")*.float_of_int freq) with _ -> !i in
|
||||
phase := message_phase;
|
||||
let else_ = if List.mem_assoc p !l && not (List.mem (p, !phase) !l) then "else " else "" in
|
||||
lprintf avr_h "%sif (i%d == %d) {\\\n" else_ p !phase;
|
||||
l := (p, !phase) :: !l;
|
||||
i := !i + freq/10;
|
||||
right ();
|
||||
lprintf avr_h "PERIODIC_SEND_%s(%s);\\\n" message_name channel_name;
|
||||
left ();
|
||||
lprintf avr_h "} \\\n"
|
||||
)
|
||||
messages;
|
||||
left ();
|
||||
lprintf avr_h "}\\\n")
|
||||
modes
|
||||
|
||||
(** [get_modules_name dir xml] Returns a list of modules name *)
|
||||
let get_modules_name = fun dir xml ->
|
||||
(* extract all "modules" sections *)
|
||||
let modules = List.map (fun x ->
|
||||
match String.lowercase (Xml.tag x) with
|
||||
"modules" -> Xml.children x
|
||||
| _ -> []
|
||||
) (Xml.children xml) in
|
||||
(* flatten the list (result is a list of "load" xml nodes) *)
|
||||
let modules = List.flatten modules in
|
||||
(* return a list of modules name *)
|
||||
let modules = List.map (fun m -> ExtXml.parse_file (dir // ExtXml.attrib m "name")) modules in
|
||||
List.map (fun m -> ExtXml.attrib m "name") modules
|
||||
|
||||
|
||||
let _ =
|
||||
if Array.length Sys.argv <> 4 then begin
|
||||
failwith (sprintf "Usage: %s <messages.xml> <telemetry.xml> frequency_in_hz" Sys.argv.(0))
|
||||
if Array.length Sys.argv <> 5 then begin
|
||||
failwith (sprintf "Usage: %s <airframe.xml> <messages.xml> <telemetry.xml> frequency_in_hz" Sys.argv.(0))
|
||||
end;
|
||||
|
||||
let freq = int_of_string(Sys.argv.(3)) in
|
||||
let freq = int_of_string(Sys.argv.(4)) in
|
||||
let telemetry_xml =
|
||||
try
|
||||
Xml.parse_file Sys.argv.(2)
|
||||
Xml.parse_file Sys.argv.(3)
|
||||
with Dtd.Check_error e -> failwith (Dtd.check_error e)
|
||||
|
||||
in
|
||||
let modules_name = get_modules_name modules_dir (ExtXml.parse_file Sys.argv.(1)) in
|
||||
|
||||
let avr_h = stdout in
|
||||
|
||||
fprintf avr_h "/* This file has been generated from %s and %s */\n" Sys.argv.(1) Sys.argv.(2);
|
||||
fprintf avr_h "/* This file has been generated from %s and %s */\n" Sys.argv.(2) Sys.argv.(3);
|
||||
fprintf avr_h "/* Please DO NOT EDIT */\n\n";
|
||||
fprintf avr_h "#ifndef _VAR_PERIODIC_H_\n";
|
||||
fprintf avr_h "#define _VAR_PERIODIC_H_\n";
|
||||
@@ -137,21 +156,21 @@ let _ =
|
||||
let i = ref 0 in
|
||||
(** For each mode of this process *)
|
||||
List.iter (fun mode ->
|
||||
let name = ExtXml.attrib mode "name" in
|
||||
Xml2h.define (sprintf "TELEMETRY_MODE_%s_%s_%s" process_name channel_name name) (string_of_int !i);
|
||||
(* Output the periods of the messages *)
|
||||
List.iter
|
||||
(fun x ->
|
||||
let p = ExtXml.attrib x "period"
|
||||
and n = ExtXml.attrib x "name" in
|
||||
Xml2h.define (sprintf "PERIOD_%s_%s_%s_%d" n process_name channel_name !i) (sprintf "(%s)" p))
|
||||
(Xml.children mode);
|
||||
incr i)
|
||||
modes;
|
||||
let name = ExtXml.attrib mode "name" in
|
||||
Xml2h.define (sprintf "TELEMETRY_MODE_%s_%s_%s" process_name channel_name name) (string_of_int !i);
|
||||
(* Output the periods of the messages *)
|
||||
List.iter
|
||||
(fun x ->
|
||||
let p = ExtXml.attrib x "period"
|
||||
and n = ExtXml.attrib x "name" in
|
||||
Xml2h.define (sprintf "PERIOD_%s_%s_%s_%d" n process_name channel_name !i) (sprintf "(%s)" p))
|
||||
(Xml.children mode);
|
||||
incr i)
|
||||
modes;
|
||||
|
||||
lprintf avr_h "#define PeriodicSend%s(%s) { /* %dHz */ \\\n" process_name channel_name freq;
|
||||
right ();
|
||||
output_modes avr_h process_name channel_name modes freq;
|
||||
output_modes avr_h process_name channel_name modes freq modules_name;
|
||||
left ();
|
||||
lprintf avr_h "}\n"
|
||||
)
|
||||
|
||||
Reference in New Issue
Block a user