Skip to content

Commit

Permalink
Both Messages modules are using shared functions with class_id as opt…
Browse files Browse the repository at this point in the history
…ional value
  • Loading branch information
xgibert committed Apr 6, 2012
1 parent b1d4eed commit f7ae806
Show file tree
Hide file tree
Showing 28 changed files with 82 additions and 207 deletions.
2 changes: 1 addition & 1 deletion conf/telemetry/aerocomm.xml
Expand Up @@ -6,7 +6,7 @@
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="1"/>
<message name="ESTIMATOR" period="1"/>
<message name="WP_MOVED_UTM" period="1.8"/>
<message name="WP_MOVED" period="1.8"/>
<message name="CIRCLE" period="1.95"/>
<message name="DESIRED" period="1.95"/>
<message name="BAT" period="1.9"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/telemetry/booz_minimal.xml
Expand Up @@ -12,7 +12,7 @@
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="10.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="2.6"/>
<message name="WP_MOVED_UTM" period="6.3"/>
<message name="WP_MOVED" period="6.3"/>
</mode>

<mode name="alternate">
Expand All @@ -22,7 +22,7 @@
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED_UTM" period="1.3"/>
<message name="WP_MOVED" period="1.3"/>
<message name="BOOZ2_CAM" period="1."/>
<message name="GPS_INT" period=".25"/>
<message name="INS" period=".25"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/telemetry/default.xml
Expand Up @@ -10,7 +10,7 @@
<message name="ATTITUDE" period="0.5"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="ENERGY" period="2.5"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="1.05"/>
<message name="BAT" period="1.1"/>
Expand All @@ -34,7 +34,7 @@
<message name="ATTITUDE" period="4"/>
<message name="GPS" period="1.05"/>
<message name="ESTIMATOR" period="1.3"/>
<message name="WP_MOVED_UTM" period="1.4"/>
<message name="WP_MOVED" period="1.4"/>
<message name="CIRCLE" period="3.05"/>
<message name="DESIRED" period="4.05"/>
<message name="BAT" period="1.1"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/telemetry/default_fixedwing_imu.xml
Expand Up @@ -10,7 +10,7 @@
<message name="ATTITUDE" period="0.1"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="ENERGY" period="2.5"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="0.2"/>
<message name="BAT" period="1.1"/>
Expand All @@ -36,7 +36,7 @@
<message name="ATTITUDE" period="4"/>
<message name="GPS" period="1.05"/>
<message name="ESTIMATOR" period="1.3"/>
<message name="WP_MOVED_UTM" period="1.4"/>
<message name="WP_MOVED" period="1.4"/>
<message name="CIRCLE" period="3.05"/>
<message name="DESIRED" period="4.05"/>
<message name="BAT" period="1.1"/>
Expand Down
4 changes: 2 additions & 2 deletions conf/telemetry/default_fixedwing_imu_9k6.xml
Expand Up @@ -10,7 +10,7 @@
<message name="ATTITUDE" period="0.7"/>
<message name="ESTIMATOR" period="0.6"/>
<message name="ENERGY" period="2.5"/>
<message name="WP_MOVED_UTM" period="1.1"/>
<message name="WP_MOVED" period="1.1"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="1.05"/>
<message name="BAT" period="1.1"/>
Expand All @@ -36,7 +36,7 @@
<message name="ATTITUDE" period="4"/>
<message name="GPS" period="1.05"/>
<message name="ESTIMATOR" period="1.3"/>
<message name="WP_MOVED_UTM" period="1.4"/>
<message name="WP_MOVED" period="1.4"/>
<message name="CIRCLE" period="3.05"/>
<message name="DESIRED" period="4.05"/>
<message name="BAT" period="1.1"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/fw_h_ctl_a.xml
Expand Up @@ -8,7 +8,7 @@
<message name="ATTITUDE" period="0.2"/>
<message name="H_CTL_A" period="0.2"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="0.2"/>
<message name="BAT" period="1.1"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/hitl.xml
Expand Up @@ -6,7 +6,7 @@
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="0.5"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="1.05"/>
<message name="BAT" period="1.1"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/iridium.xml
Expand Up @@ -9,7 +9,7 @@

<message name="ATTITUDE" period="4." phase="1"/>
<message name="DL_VALUE" period="4." phase="3"/>
<message name="WP_MOVED_UTM" period="4." phase="3"/>
<message name="WP_MOVED" period="4." phase="3"/>

<message name="DESIRED" period="8." phase="1"/>
<!-- Only one of the following is active at the same time: give them same time stamp -->
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/minimal.xml
Expand Up @@ -6,7 +6,7 @@
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="1"/>
<message name="ESTIMATOR" period="1"/>
<message name="WP_MOVED_UTM" period="1"/>
<message name="WP_MOVED" period="1"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="2.05"/>
<message name="BAT" period="1.1"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/osam_imu.xml
Expand Up @@ -6,7 +6,7 @@
<message name="ALIVE" period="5"/>
<message name="ATTITUDE" period="0.5"/>
<message name="ESTIMATOR" period="0.5"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="CIRCLE" period="1.05"/>
<message name="DESIRED" period="1.05"/>
<message name="BAT" period="1.1"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/telemetry_booz2.xml
Expand Up @@ -12,7 +12,7 @@
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED_UTM" period="1.3"/>
<message name="WP_MOVED" period="1.3"/>
<message name="BOOZ2_CAM" period="1."/>
<message name="GPS_INT" period=".25"/>
<message name="INS" period=".25"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/telemetry_jtm.xml
Expand Up @@ -12,7 +12,7 @@
<message name="ALIVE" period="2.1"/>
<message name="INS_REF" period="5.1"/>
<message name="ROTORCRAFT_NAV_STATUS" period="1.6"/>
<message name="WP_MOVED_UTM" period="1.3"/>
<message name="WP_MOVED" period="1.3"/>
<message name="BOOZ2_CAM" period="1."/>
<message name="GPS_INT" period=".25"/>
<message name="INS" period=".25"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/tl.xml
Expand Up @@ -15,7 +15,7 @@
<message name="TL_ESTIMATOR" period="0.5"/>
<message name="NAVIGATION_REF" period="9"/>
<message name="NAVIGATION" period="1"/>
<message name="WP_MOVED_UTM" period="0.5"/>
<message name="WP_MOVED" period="0.5"/>
<message name="LOOP" period="0.5"/>
<message name="TL_DEBUG" period="0.5"/>
</mode>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/ugv.xml
Expand Up @@ -4,7 +4,7 @@
<process name="Ap">
<mode name="default">
<message name="ALIVE" period="5"/>
<message name="WP_MOVED_UTM" period="2"/>
<message name="WP_MOVED" period="2"/>
<message name="DESIRED" period="1.05"/>
<message name="NAVIGATION_REF" period="9."/>
<message name="PPRZ_MODE" period="5."/>
Expand Down
2 changes: 1 addition & 1 deletion conf/telemetry/xbee868.xml
Expand Up @@ -9,7 +9,7 @@

<message name="ATTITUDE" period="6." phase="0"/>
<message name="DL_VALUE" period="3." phase="0"/>
<message name="WP_MOVED_UTM" period="6." phase="3"/>
<message name="WP_MOVED" period="6." phase="3"/>

<message name="DESIRED" period="6." phase="0"/>
<message name="SEGMENT" period="6." phase="0"/>
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/firmwares/fixedwing/ap_downlink.h
Expand Up @@ -117,7 +117,7 @@ extern uint8_t telemetry_mode_Ap_DefaultChannel;
}


#define PERIODIC_SEND_WP_MOVED_UTM(_trans, _dev) { \
#define PERIODIC_SEND_WP_MOVED(_trans, _dev) { \
static uint8_t i; \
i++; if (i >= nb_waypoint) i = 0; \
DownlinkSendWp(_trans, _dev, i); \
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/firmwares/rotorcraft/telemetry.h
Expand Up @@ -703,7 +703,7 @@ extern uint8_t telemetry_mode_Main_DefaultChannel;
} \
}

#define PERIODIC_SEND_WP_MOVED_UTM(_trans, _dev) { \
#define PERIODIC_SEND_WP_MOVED(_trans, _dev) { \
static uint8_t i; \
i++; if (i >= nb_waypoint) i = 0; \
DOWNLINK_SEND_WP_MOVED_ENU(_trans, _dev, \
Expand Down
4 changes: 2 additions & 2 deletions sw/ground_segment/tmtc/ivy2udp.ml
Expand Up @@ -61,7 +61,7 @@ let () =
let get_ivy_message = fun _ args ->
try
let (msg_id, vs) = Tm_Pprz.values_of_string args.(0) in
let payload = Tm_Pprz.payload_of_values (int_of_string !id) (Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let payload = Tm_Pprz.payload_of_values (int_of_string !id) ~class_id:(Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let buf = Pprz.Transport.packet payload in
let n = String.length buf in
let n' = Unix.sendto socket buf 0 n [] sockaddr in
Expand All @@ -87,7 +87,7 @@ let () =
let use_dl_message = fun payload ->
Debug.trace 'x' (Debug.xprint (Serial.string_of_payload payload));
let (packet_seq, ac_id, class_id, msg_id, values) = Dl_Pprz.values_of_payload payload in
let msg = Dl_Pprz.message_of_id class_id msg_id in
let msg = Dl_Pprz.message_of_id ~class_id:class_id msg_id in
Dl_Pprz.message_send "ground_dl" msg.Pprz.name values in

assert (PprzTransport.parse use_dl_message b = n)
Expand Down
4 changes: 2 additions & 2 deletions sw/ground_segment/tmtc/ivy_tcp_aircraft.ml
Expand Up @@ -32,7 +32,7 @@ let () =
let get_ivy_message = fun _ args ->
try
let (msg_id, vs) = Tm_Pprz.values_of_string args.(0) in
let payload = Tm_Pprz.payload_of_values (int_of_string !id) (Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let payload = Tm_Pprz.payload_of_values (int_of_string !id) ~class_id:(Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let buf = Pprz.Transport.packet payload in
fprintf o "%s%!" buf
with _ -> () in
Expand All @@ -51,7 +51,7 @@ let () =
let use_dl_message = fun payload ->
Debug.trace 'x' (Debug.xprint (Serial.string_of_payload payload));
let (packet_seq, ac_id, class_id, msg_id, values) = Dl_Pprz.values_of_payload payload in
let msg = Dl_Pprz.message_of_id class_id msg_id in
let msg = Dl_Pprz.message_of_id ~class_id:class_id msg_id in
Dl_Pprz.message_send "ground_dl" msg.Pprz.name values in

assert (PprzTransport.parse use_dl_message b = n)
Expand Down
4 changes: 2 additions & 2 deletions sw/ground_segment/tmtc/ivy_tcp_controller.ml
Expand Up @@ -39,7 +39,7 @@ let () =
let use_tele_message = fun payload ->
Debug.trace 'x' (Debug.xprint (Serial.string_of_payload payload));
let (packet_seq, ac_id, class_id, msg_id, values) = Tm_Pprz.values_of_payload payload in
let msg = Tm_Pprz.message_of_id class_id msg_id in
let msg = Tm_Pprz.message_of_id ~class_id:class_id msg_id in
Tm_Pprz.message_send (string_of_int ac_id) msg.Pprz.name values in

ignore (PprzTransport.parse use_tele_message b)
Expand All @@ -57,7 +57,7 @@ let () =
try
let (msg_id, vs) = Dl_Pprz.values_of_string args.(0) in
let ac_id = Pprz.int_assoc "ac_id" vs in
let payload = Dl_Pprz.payload_of_values ac_id (Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let payload = Dl_Pprz.payload_of_values ac_id ~class_id:(Pprz.class_id_of_msg_args args.(0)) msg_id vs in
let buf = Pprz.Transport.packet payload in
fprintf o "%s%!" buf
with exc -> prerr_endline (Printexc.to_string exc) in
Expand Down
8 changes: 4 additions & 4 deletions sw/ground_segment/tmtc/link.ml
Expand Up @@ -207,7 +207,7 @@ let use_tele_message = fun ?udp_peername ?raw_data_size payload ->
try
let (packet_seq ,ac_id, class_id, msg_id, values) = Tm_Pprz.values_of_payload payload in
ignore (check_down_packet_sequence ac_id packet_seq);
let msg = Tm_Pprz.message_of_id class_id msg_id in
let msg = Tm_Pprz.message_of_id ~class_id:class_id msg_id in
send_message_over_ivy (string_of_int ac_id) msg.Pprz.name values;
update_status ?udp_peername ac_id raw_data_size (msg.Pprz.name = "PONG")
with
Expand Down Expand Up @@ -431,7 +431,7 @@ let message_uplink = fun device ->
let class_id = Pprz.class_id_of_msg name in
let msg_id, _ = Dl_Pprz.message_of_name name in
let gen_packet_seq = get_up_packet_sequence ac_id in
let s = Dl_Pprz.payload_of_values ~gen_packet_seq:gen_packet_seq my_id class_id msg_id vs in
let s = Dl_Pprz.payload_of_values ~gen_packet_seq:gen_packet_seq my_id ~class_id:class_id msg_id vs in
send ac_id device s High in
let set_forwarder = fun name ->
ignore (Dl_Pprz.message_bind name (forwarder name)) in
Expand All @@ -440,7 +440,7 @@ let message_uplink = fun device ->
Debug.call 'f' (fun f -> fprintf f "broadcast %s\n" name);
let class_id = Pprz.class_id_of_msg name in
let msg_id, _ = Dl_Pprz.message_of_name name in
let payload = Dl_Pprz.payload_of_values ~gen_packet_seq:(get_up_packet_sequence 0) my_id class_id msg_id vs in
let payload = Dl_Pprz.payload_of_values ~gen_packet_seq:(get_up_packet_sequence 0) my_id ~class_id:class_id msg_id vs in
broadcast device payload Low in
let set_broadcaster = fun name ->
ignore (Dl_Pprz.message_bind name (broadcaster name)) in
Expand All @@ -459,7 +459,7 @@ let send_ping_msg = fun device ->
(fun ac_id status ->
let class_id = Pprz.class_id_of_msg "PING" in
let msg_id, _ = Dl_Pprz.message_of_name "PING" in
let s = Dl_Pprz.payload_of_values ~gen_packet_seq:(get_up_packet_sequence ac_id) my_id class_id msg_id [] in
let s = Dl_Pprz.payload_of_values ~gen_packet_seq:(get_up_packet_sequence ac_id) my_id ~class_id:class_id msg_id [] in
send ac_id device s High;
status.last_ping <- Unix.gettimeofday ()
)
Expand Down
7 changes: 3 additions & 4 deletions sw/ground_segment/tmtc/server.ml
Expand Up @@ -136,14 +136,13 @@ let log = fun ?timestamp logging ac_name msg_name values ->

(** Callback for a message from a registered A/C *)
let ac_msg = fun messages_xml logging ac_name ac ->
(*let module Tele_Pprz = Pprz.MessagesOfXml(struct let xml = messages_xml let selection = "downlink" and mode = "type" end) in*) (* XGGDEBUG:DYNMOD: What is doing this? I NEED THE FULL MODULE TO USE MESSAGE_OF_ID *)
let module Tele_Pprz = Pprz.Messages_of_type (struct let class_type = "downlink" end) in
let module Tele_Pprz = Pprz.MessagesOfXml(struct let xml = messages_xml let selection = "downlink" and mode = Pprz.Type and sel_class_id = None end) in
fun ts m ->
try
let timestamp = try Some (float_of_string ts) with _ -> None in
let (msg_id, values) = Tele_Pprz.values_of_string m in
let cls_id = Pprz.class_id_of_msg_args m in
let msg = Tele_Pprz.message_of_id cls_id msg_id in
let msg = Tele_Pprz.message_of_id ~class_id:cls_id msg_id in
log ?timestamp logging ac_name msg.Pprz.name values;
Fw_server.log_and_parse ac_name ac msg values;
Rotorcraft_server.log_and_parse ac_name ac msg values
Expand Down Expand Up @@ -681,7 +680,7 @@ let raw_datalink = fun logging _sender vs ->
and m = Pprz.string_assoc "message" vs in
let msg_id, vs = Dl_Pprz.values_of_string_unsorted m in
let cls_id = Pprz.class_id_of_msg_args_unsorted m in
let msg = Dl_Pprz.message_of_id cls_id msg_id in
let msg = Dl_Pprz.message_of_id ~class_id:cls_id msg_id in
Dl_Pprz.message_send dl_id msg.Pprz.name vs;
log logging ac_id msg.Pprz.name vs

Expand Down

0 comments on commit f7ae806

Please sign in to comment.