mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-02 05:17:03 +08:00
changing telemetry frequency
This commit is contained in:
+8
-2
@@ -32,6 +32,11 @@ MESSAGES_XML = $(CONF)/messages.xml
|
|||||||
ACINCLUDE = $(PAPARAZZI_HOME)/var/$(AIRCRAFT)
|
ACINCLUDE = $(PAPARAZZI_HOME)/var/$(AIRCRAFT)
|
||||||
AIRCRAFT_CONF_DIR = $(ACINCLUDE)/conf
|
AIRCRAFT_CONF_DIR = $(ACINCLUDE)/conf
|
||||||
AIRFRAME_H=$(ACINCLUDE)/airframe.h
|
AIRFRAME_H=$(ACINCLUDE)/airframe.h
|
||||||
|
|
||||||
|
ifndef PERIODIC_FREQ
|
||||||
|
PERIODIC_FREQ = 60
|
||||||
|
endif
|
||||||
|
|
||||||
PERIODIC_H=$(ACINCLUDE)/periodic.h
|
PERIODIC_H=$(ACINCLUDE)/periodic.h
|
||||||
RADIO_H=$(ACINCLUDE)/radio.h
|
RADIO_H=$(ACINCLUDE)/radio.h
|
||||||
FLIGHT_PLAN_H=$(ACINCLUDE)/flight_plan.h
|
FLIGHT_PLAN_H=$(ACINCLUDE)/flight_plan.h
|
||||||
@@ -75,9 +80,10 @@ $(RADIO_H) : $(CONF)/$(RADIO) $(CONF_XML) $(TOOLS)/gen_radio.out
|
|||||||
$(Q)mv /tmp/radio.h $@
|
$(Q)mv /tmp/radio.h $@
|
||||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)/radios
|
$(Q)cp $< $(AIRCRAFT_CONF_DIR)/radios
|
||||||
|
|
||||||
$(PERIODIC_H) : $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TELEMETRY)
|
include $(MAKEFILE_AC)
|
||||||
|
$(PERIODIC_H) : $(MESSAGES_XML) $(CONF_XML) $(CONF)/$(TELEMETRY) $(MAKEFILE_AC)
|
||||||
@echo BUILD $@
|
@echo BUILD $@
|
||||||
$(Q)$(TOOLS)/gen_periodic.out $(MESSAGES_XML) $(CONF)/$(TELEMETRY) > $@
|
$(Q)$(TOOLS)/gen_periodic.out $(MESSAGES_XML) $(CONF)/$(TELEMETRY) $(PERIODIC_FREQ) > $@
|
||||||
$(Q)chmod a+r $@
|
$(Q)chmod a+r $@
|
||||||
$(Q)cp $< $(AIRCRAFT_CONF_DIR)
|
$(Q)cp $< $(AIRCRAFT_CONF_DIR)
|
||||||
$(Q)cp $(CONF)/$(TELEMETRY) $(AIRCRAFT_CONF_DIR)/telemetry
|
$(Q)cp $(CONF)/$(TELEMETRY) $(AIRCRAFT_CONF_DIR)/telemetry
|
||||||
|
|||||||
@@ -26,6 +26,7 @@
|
|||||||
|
|
||||||
open Printf
|
open Printf
|
||||||
|
|
||||||
|
|
||||||
let margin = ref 0
|
let margin = ref 0
|
||||||
let step = 2
|
let step = 2
|
||||||
|
|
||||||
@@ -36,9 +37,9 @@ let lprintf = fun c f ->
|
|||||||
fprintf c "%s" (String.make !margin ' ');
|
fprintf c "%s" (String.make !margin ' ');
|
||||||
fprintf c f
|
fprintf c f
|
||||||
|
|
||||||
let freq = 60
|
let freq = ref 60
|
||||||
let min_period = 1./.float freq
|
let min_period = 1./.float !freq
|
||||||
let max_period = 65536. /. float freq
|
let max_period = 65536. /. float !freq
|
||||||
|
|
||||||
let remove_dup = fun l ->
|
let remove_dup = fun l ->
|
||||||
let rec loop = fun l ->
|
let rec loop = fun l ->
|
||||||
@@ -64,7 +65,7 @@ let output_modes = fun avr_h process_name modes ->
|
|||||||
let p = float_of_string (ExtXml.attrib x "period") in
|
let p = float_of_string (ExtXml.attrib x "period") in
|
||||||
if p < min_period || p > max_period then
|
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");
|
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)))))
|
(x, min 65535 (max 1 (int_of_float (p*.float_of_int !freq)))))
|
||||||
(Xml.children mode)
|
(Xml.children mode)
|
||||||
in
|
in
|
||||||
let modulos = remove_dup (List.map snd messages) in
|
let modulos = remove_dup (List.map snd messages) in
|
||||||
@@ -87,7 +88,7 @@ let output_modes = fun avr_h process_name modes ->
|
|||||||
let else_ = if List.mem_assoc p !l && not (List.mem (p, !i) !l) then "else " else "" in
|
let else_ = if List.mem_assoc p !l && not (List.mem (p, !i) !l) then "else " else "" in
|
||||||
lprintf avr_h "%sif (i%d == %d) {\\\n" else_ p !i;
|
lprintf avr_h "%sif (i%d == %d) {\\\n" else_ p !i;
|
||||||
l := (p, !i) :: !l;
|
l := (p, !i) :: !l;
|
||||||
i := !i + freq/10;
|
i := !i + !freq/10;
|
||||||
right ();
|
right ();
|
||||||
lprintf avr_h "PERIODIC_SEND_%s();\\\n" message_name;
|
lprintf avr_h "PERIODIC_SEND_%s();\\\n" message_name;
|
||||||
left ();
|
left ();
|
||||||
@@ -100,10 +101,11 @@ let output_modes = fun avr_h process_name modes ->
|
|||||||
|
|
||||||
|
|
||||||
let _ =
|
let _ =
|
||||||
if Array.length Sys.argv <> 3 then begin
|
if Array.length Sys.argv <> 4 then begin
|
||||||
failwith (sprintf "Usage: %s <messages.xml> <telemetry.xml>" Sys.argv.(0))
|
failwith (sprintf "Usage: %s <messages.xml> <telemetry.xml> frequency_in_hz" Sys.argv.(0))
|
||||||
end;
|
end;
|
||||||
|
|
||||||
|
freq := int_of_string(Sys.argv.(3));
|
||||||
let telemetry_xml =
|
let telemetry_xml =
|
||||||
try
|
try
|
||||||
Xml.parse_file Sys.argv.(2)
|
Xml.parse_file Sys.argv.(2)
|
||||||
@@ -140,7 +142,7 @@ let _ =
|
|||||||
incr i)
|
incr i)
|
||||||
modes;
|
modes;
|
||||||
|
|
||||||
lprintf avr_h "#define PeriodicSend%s() { /* %dHz */ \\\n" process_name freq;
|
lprintf avr_h "#define PeriodicSend%s() { /* %dHz */ \\\n" process_name !freq;
|
||||||
right ();
|
right ();
|
||||||
output_modes avr_h process_name modes;
|
output_modes avr_h process_name modes;
|
||||||
left ();
|
left ();
|
||||||
|
|||||||
Reference in New Issue
Block a user