mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-02 13:27:32 +08:00
*** empty log message ***
This commit is contained in:
@@ -94,6 +94,7 @@
|
|||||||
<program name="receive"/>
|
<program name="receive"/>
|
||||||
<program name="sim"><arg flag="-a" constant="Thon1"/></program>
|
<program name="sim"><arg flag="-a" constant="Thon1"/></program>
|
||||||
<program name="map 2d ml"/>
|
<program name="map 2d ml"/>
|
||||||
|
<program name="messages"><arg flag="-c" constant="telemetry_ap:1"/><arg flag="-c" constant="ground"/></program>
|
||||||
</session>
|
</session>
|
||||||
|
|
||||||
<session name="flight microjet modem">
|
<session name="flight microjet modem">
|
||||||
|
|||||||
+36
-41
@@ -4,39 +4,39 @@
|
|||||||
<!-- messages from modem or sim to server -->
|
<!-- messages from modem or sim to server -->
|
||||||
<class name="telemetry_ap" ID="0x40">
|
<class name="telemetry_ap" ID="0x40">
|
||||||
|
|
||||||
<message name="BOOT" ID="0x01">
|
<message name="BOOT" ID="1">
|
||||||
<field name="version" type="uint16"></field>
|
<field name="version" type="uint16"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="CALIB_START" ID="0x02">
|
<message name="CALIB_START" ID="2">
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="CALIB_CONTRAST" ID="0x03">
|
<message name="CALIB_CONTRAST" ID="3">
|
||||||
<field name="adc" type="int16"></field>
|
<field name="adc" type="int16"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="TAKEOFF" ID="0x04">
|
<message name="TAKEOFF" ID="4">
|
||||||
<field name="cpu_time" type="uint16" unit="s"></field>
|
<field name="cpu_time" type="uint16" unit="s"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="RAD_OF_IR" ID="0x05">
|
<message name="RAD_OF_IR" ID="5">
|
||||||
<field name="ir" type="int16"></field>
|
<field name="ir" type="int16"></field>
|
||||||
<field name="rad" type="int16" unit="decideg"></field>
|
<field name="rad" type="int16" unit="decideg"></field>
|
||||||
<field name="rad_of_ir" type="float" format="%.4f"></field>
|
<field name="rad_of_ir" type="float" format="%.4f"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="ATTITUDE" ID="0x06" period="0.5" >
|
<message name="ATTITUDE" ID="6" period="0.5" >
|
||||||
<field name="phi" type="int8" unit="deg"></field>
|
<field name="phi" type="int8" unit="deg"></field>
|
||||||
<field name="psi" type="int8" unit="deg"></field>
|
<field name="psi" type="int8" unit="deg"></field>
|
||||||
<field name="theta" type="int8" unit="deg"></field>
|
<field name="theta" type="int8" unit="deg"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="ADC" ID="0x07" period="0.5" >
|
<message name="ADC" ID="7" period="0.5" >
|
||||||
<field name="roll" type="int16"></field>
|
<field name="roll" type="int16"></field>
|
||||||
<field name="pitch" type="int16"></field>
|
<field name="pitch" type="int16"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="GPS" ID="0x08">
|
<message name="GPS" ID="8">
|
||||||
<field name="mode" type="uint8" unit="byte_mask"></field>
|
<field name="mode" type="uint8" unit="byte_mask"></field>
|
||||||
<field name="utm_east" type="int32" unit="cm"></field>
|
<field name="utm_east" type="int32" unit="cm"></field>
|
||||||
<field name="utm_north" type="int32" unit="cm"></field>
|
<field name="utm_north" type="int32" unit="cm"></field>
|
||||||
@@ -48,13 +48,13 @@
|
|||||||
<field name="utm_zone" type="uint8"></field>
|
<field name="utm_zone" type="uint8"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="NAVIGATION_REF" ID="0x09" period="10" >
|
<message name="NAVIGATION_REF" ID="0x09" period="9" >
|
||||||
<field name="utm_east" type="int32" unit="m"></field>
|
<field name="utm_east" type="int32" unit="m"></field>
|
||||||
<field name="utm_north" type="int32" unit="m"></field>
|
<field name="utm_north" type="int32" unit="m"></field>
|
||||||
<field name="utm_zone" type="uint8"></field>
|
<field name="utm_zone" type="uint8"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="NAVIGATION" ID="0x0A">
|
<message name="NAVIGATION" ID="10">
|
||||||
<field name="cur_block" type="uint8"></field>
|
<field name="cur_block" type="uint8"></field>
|
||||||
<field name="cur_stage" type="uint8"></field>
|
<field name="cur_stage" type="uint8"></field>
|
||||||
<field name="pos_x" type="int16" unit="m"></field>
|
<field name="pos_x" type="int16" unit="m"></field>
|
||||||
@@ -64,7 +64,7 @@
|
|||||||
<field name="dist2_home" type="float" format="%.1f" unit="m^2"></field>
|
<field name="dist2_home" type="float" format="%.1f" unit="m^2"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="PPRZ_MODE" ID="0x0B" period="5" >
|
<message name="PPRZ_MODE" ID="11" period="5" >
|
||||||
<field name="ap_mode" type="uint8" values="MANUAL|AUTO1|AUTO2|HOME"/>
|
<field name="ap_mode" type="uint8" values="MANUAL|AUTO1|AUTO2|HOME"/>
|
||||||
<field name="ap_altitude" type="uint8" values="MANUAL|AUTO_GAZ|AUTO_CLIMB|AUTO_ALT"/>
|
<field name="ap_altitude" type="uint8" values="MANUAL|AUTO_GAZ|AUTO_CLIMB|AUTO_ALT"/>
|
||||||
<field name="if_calib_mode" type="uint8" values="NONE|DOWN|UP"/>
|
<field name="if_calib_mode" type="uint8" values="NONE|DOWN|UP"/>
|
||||||
@@ -72,7 +72,7 @@
|
|||||||
<field name="lls_calib" type="uint8" values="LLS_CALIB_MODE_OFF|LLS_CALIB_MODE_ON"/>
|
<field name="lls_calib" type="uint8" values="LLS_CALIB_MODE_OFF|LLS_CALIB_MODE_ON"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="BAT" ID="0x0C" period="2" >
|
<message name="BAT" ID="12" period="2" >
|
||||||
<field name="desired_gaz" type="int16" unit="pprz"></field>
|
<field name="desired_gaz" type="int16" unit="pprz"></field>
|
||||||
<field name="voltage" type="uint8" unit="1e-1V"></field>
|
<field name="voltage" type="uint8" unit="1e-1V"></field>
|
||||||
<field name="flight_time" type="uint16" unit="s"></field>
|
<field name="flight_time" type="uint16" unit="s"></field>
|
||||||
@@ -82,7 +82,7 @@
|
|||||||
<field name="energy" type="uint16" unit="mAh"/>
|
<field name="energy" type="uint16" unit="mAh"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="DEBUG" ID="0x0D" period="5" >
|
<message name="DEBUG" ID="13" period="5" >
|
||||||
<field name="i2c_nb_err" type="uint8"></field>
|
<field name="i2c_nb_err" type="uint8"></field>
|
||||||
<field name="i2c_mcu1_nb_err" type="uint8"></field>
|
<field name="i2c_mcu1_nb_err" type="uint8"></field>
|
||||||
<field name="modem_nb_err" type="uint8"></field>
|
<field name="modem_nb_err" type="uint8"></field>
|
||||||
@@ -90,18 +90,18 @@
|
|||||||
<field name="ppm_rate" type="uint8"></field>
|
<field name="ppm_rate" type="uint8"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="CALIBRATION" ID="0x0E" period="2">
|
<message name="CALIBRATION" ID="14" period="2">
|
||||||
<field name="climb_sum_err" type="float" format="%.1f"></field>
|
<field name="climb_sum_err" type="float" format="%.1f"></field>
|
||||||
<field name="climb_pgain" type="float" format="%.3f"></field>
|
<field name="climb_pgain" type="float" format="%.3f"></field>
|
||||||
<field name="course_pgain" type="float" format="%.3f"></field>
|
<field name="course_pgain" type="float" format="%.3f"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="SETTINGS" ID="0x0F" period="0.5">
|
<message name="SETTINGS" ID="15" period="0.5">
|
||||||
<field name="slider_1_val" type="float"></field>
|
<field name="slider_1_val" type="float"></field>
|
||||||
<field name="slider_2_val" type="float"></field>
|
<field name="slider_2_val" type="float"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="DESIRED" ID="0x10" period="1">
|
<message name="DESIRED" ID="16" period="1">
|
||||||
<field name="roll" type="float" format="%.2f"/>
|
<field name="roll" type="float" format="%.2f"/>
|
||||||
<field name="pitch" type="float" format="%.2f"/>
|
<field name="pitch" type="float" format="%.2f"/>
|
||||||
<field name="desired_x" type="float" format="%.0f"/>
|
<field name="desired_x" type="float" format="%.0f"/>
|
||||||
@@ -110,7 +110,7 @@
|
|||||||
<field name="desired_climb" type="float" format="%.1f"></field>
|
<field name="desired_climb" type="float" format="%.1f"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="IMU" ID="0x11">
|
<message name="IMU" ID="17">
|
||||||
<field name="gyro_x" type="float"/>
|
<field name="gyro_x" type="float"/>
|
||||||
<field name="gyro_y" type="float"/>
|
<field name="gyro_y" type="float"/>
|
||||||
<field name="gyro_z" type="float"/>
|
<field name="gyro_z" type="float"/>
|
||||||
@@ -119,7 +119,7 @@
|
|||||||
<field name="accel_z" type="float"/>
|
<field name="accel_z" type="float"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="RAW_IMU" ID="0x12">
|
<message name="RAW_IMU" ID="17">
|
||||||
<field name="raw_gx" type="uint16"/>
|
<field name="raw_gx" type="uint16"/>
|
||||||
<field name="raw_gy" type="uint16"/>
|
<field name="raw_gy" type="uint16"/>
|
||||||
<field name="raw_gz" type="uint16"/>
|
<field name="raw_gz" type="uint16"/>
|
||||||
@@ -128,7 +128,7 @@
|
|||||||
<field name="raw_az" type="uint16"/>
|
<field name="raw_az" type="uint16"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="KALMAN" ID="0x13">
|
<message name="KALMAN" ID="18">
|
||||||
<field name="phi" type="float" format="%.3f"/>
|
<field name="phi" type="float" format="%.3f"/>
|
||||||
<field name="phi_dot" type="float" format="%.3f"/>
|
<field name="phi_dot" type="float" format="%.3f"/>
|
||||||
<field name="phi_bias" type="float" format="%.3f"/>
|
<field name="phi_bias" type="float" format="%.3f"/>
|
||||||
@@ -137,31 +137,31 @@
|
|||||||
<field name="theta_bias" type="float" format="%.3f"/>
|
<field name="theta_bias" type="float" format="%.3f"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="IDENT" ID="0x14" period="10">
|
<message name="IDENT" ID="19" period="10">
|
||||||
<field name="id" type="uint8"/>
|
<field name="id" type="uint8"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="CAM" ID="0x15">
|
<message name="CAM" ID="20">
|
||||||
<field name="phi" type="int8" unit="deg"/>
|
<field name="phi" type="int8" unit="deg"/>
|
||||||
<field name="theta" type="int8" unit="deg"/>
|
<field name="theta" type="int8" unit="deg"/>
|
||||||
<field name="target_x" type="int16" unit="m"/>
|
<field name="target_x" type="int16" unit="m"/>
|
||||||
<field name="target_y" type="int16" unit="m"/>
|
<field name="target_y" type="int16" unit="m"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="CIRCLE" ID="0x16">
|
<message name="CIRCLE" ID="21">
|
||||||
<field name="center_x" type="int16" unit="m"/>
|
<field name="center_x" type="int16" unit="m"/>
|
||||||
<field name="center_y" type="int16" unit="m"/>
|
<field name="center_y" type="int16" unit="m"/>
|
||||||
<field name="radius" type="int16" unit="m"/>
|
<field name="radius" type="int16" unit="m"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="SEGMENT" ID="0x17">
|
<message name="SEGMENT" ID="22">
|
||||||
<field name="segment_x_1" type="int16" unit="m"/>
|
<field name="segment_x_1" type="int16" unit="m"/>
|
||||||
<field name="segment_y_1" type="int16" unit="m"/>
|
<field name="segment_y_1" type="int16" unit="m"/>
|
||||||
<field name="segment_x_2" type="int16" unit="m"/>
|
<field name="segment_x_2" type="int16" unit="m"/>
|
||||||
<field name="segment_y_2" type="int16" unit="m"/>
|
<field name="segment_y_2" type="int16" unit="m"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="DOWNLINK_STATUS" ID="0x02">
|
<message name="DOWNLINK_STATUS" ID="23">
|
||||||
<field name="run_time" type="uint32" unit="s"></field>
|
<field name="run_time" type="uint32" unit="s"></field>
|
||||||
<field name="rx_bytes" type="uint32"></field>
|
<field name="rx_bytes" type="uint32"></field>
|
||||||
<field name="rx_msgs" type="uint32"></field>
|
<field name="rx_msgs" type="uint32"></field>
|
||||||
@@ -170,7 +170,7 @@
|
|||||||
<field name="rx_msgs_rate" type="float" format="%.1f"></field>
|
<field name="rx_msgs_rate" type="float" format="%.1f"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="MODEM_STATUS" ID="0x03">
|
<message name="MODEM_STATUS" ID="24">
|
||||||
<field name="detected" type="uint8"></field>
|
<field name="detected" type="uint8"></field>
|
||||||
<field name="valim" type="float" format="%.1f"></field>
|
<field name="valim" type="float" format="%.1f"></field>
|
||||||
<field name="cd" type="uint8"></field>
|
<field name="cd" type="uint8"></field>
|
||||||
@@ -179,7 +179,7 @@
|
|||||||
<field name="nb_err" type="uint32"></field>
|
<field name="nb_err" type="uint32"></field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="SVINFO" id="20">
|
<message name="SVINFO" id="25">
|
||||||
<field name="chn" type="uint8"/>
|
<field name="chn" type="uint8"/>
|
||||||
<field name="SVID" type="uint8"/>
|
<field name="SVID" type="uint8"/>
|
||||||
<field name="Flags" type="uint8"/>
|
<field name="Flags" type="uint8"/>
|
||||||
@@ -345,21 +345,14 @@
|
|||||||
<field name="energy" type="float" unit="Wh"/>
|
<field name="energy" type="float" unit="Wh"/>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="SATS" ID="16">
|
<message name="SVSINFO" ID="16">
|
||||||
<field name="itow" type="uint32" unit="ms"/>
|
<field name="ac_id" type="string"/>
|
||||||
<field name="nch" type="uint8"/>
|
<field name="svid" type="string" format="csv"/>
|
||||||
<field name="res1" type="uint8"/>
|
<field name="flags" type="string" format="csv"/>
|
||||||
<field name="res2" type="uint8"/>
|
<field name="qi" type="string" format="csv" values="IDLE|SEARCH|SEARCH|UNUSABLE|CODELOCK|CARRIERLOCK|CARRIERLOCK|RECEIVING"/>
|
||||||
<block name="sats" times="nch">
|
<field name="cno" type="string" format="csv" unit="dbHz"/>
|
||||||
<field name="chn" type="uint8"/>
|
<field name="elev" type="string" format="csv" unit="deg"/>
|
||||||
<field name="svid" type="uint8"/>
|
<field name="azim" type="string" format="csv" unit="deg"/>
|
||||||
<field name="flags" type="uint8"/>
|
|
||||||
<field name="qi" type="int8"/>
|
|
||||||
<field name="cno" type="float" unit="dbHz"/>
|
|
||||||
<field name="elev" type="float" unit="deg"/>
|
|
||||||
<field name="azim" type="float" unit="deg"/>
|
|
||||||
<field name="prres" type="float" unit="cm"/>
|
|
||||||
</block>
|
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
<message name="FLY_BY_WIRE" id="17">
|
<message name="FLY_BY_WIRE" id="17">
|
||||||
@@ -379,6 +372,8 @@
|
|||||||
<message name="INFLIGH_CALIB" id="19">
|
<message name="INFLIGH_CALIB" id="19">
|
||||||
<field name="ac_id" type="string"/>
|
<field name="ac_id" type="string"/>
|
||||||
<field name="if_mode" type="uint8" values="DOWN|OFF|UP"></field>
|
<field name="if_mode" type="uint8" values="DOWN|OFF|UP"></field>
|
||||||
|
<field name="if_value1" type="float"></field>
|
||||||
|
<field name="if_value2" type="float"></field>
|
||||||
</message>
|
</message>
|
||||||
</class>
|
</class>
|
||||||
|
|
||||||
|
|||||||
Vendored
+1
-1
@@ -7,6 +7,6 @@ Standards-Version: 3.6.1
|
|||||||
|
|
||||||
Package: paparazzi
|
Package: paparazzi
|
||||||
Architecture: i386
|
Architecture: i386
|
||||||
Depends: ivy-c-dev, ivy-c, ivy-perl, libsubject-perl, zinc-perl, zinc-tk, ivy-ocaml, xml-light-ocaml, libxml-dom-perl, libpcre3-dev, liblablgtk2-ocaml-dev, gcc-avr, avr-libc, binutils-avr, libexpect-perl, libgnomecanvas2-dev, libcamlimages-ocaml-dev, uisp, libfile-ncopy-perl, libtext-csv-perl, digikit
|
Depends: ivy-c-dev, ivy-c, ivy-perl, libsubject-perl, zinc-perl, zinc-tk, ivy-ocaml, xml-light-ocaml, libxml-dom-perl, libpcre3-dev, liblablgtk2-ocaml-dev, gcc-avr, avr-libc, binutils-avr, libexpect-perl, libgnomecanvas2-dev, libcamlimages-ocaml-dev, uisp, libfile-ncopy-perl, libtext-csv-perl, digikit, make, gcc, patch
|
||||||
Description: Paparazzi Meta Package
|
Description: Paparazzi Meta Package
|
||||||
|
|
||||||
|
|||||||
@@ -48,6 +48,8 @@ type ac_cam = {
|
|||||||
|
|
||||||
type inflight_calib = {
|
type inflight_calib = {
|
||||||
mutable if_mode : int; (* DOWN|OFF|UP *)
|
mutable if_mode : int; (* DOWN|OFF|UP *)
|
||||||
|
mutable if_val1 : float;
|
||||||
|
mutable if_val2 : float
|
||||||
}
|
}
|
||||||
|
|
||||||
type contrast_status = string (** DEFAULT|WAITING|SET *)
|
type contrast_status = string (** DEFAULT|WAITING|SET *)
|
||||||
@@ -66,6 +68,25 @@ type fbw = {
|
|||||||
mutable rc_mode : rc_mode;
|
mutable rc_mode : rc_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
let gps_nb_channels = 16
|
||||||
|
type svinfo = {
|
||||||
|
svid : int;
|
||||||
|
flags : int;
|
||||||
|
qi : int;
|
||||||
|
cno : int;
|
||||||
|
elev : int;
|
||||||
|
azim : int
|
||||||
|
}
|
||||||
|
|
||||||
|
let svinfo_init = {
|
||||||
|
svid = 0 ;
|
||||||
|
flags = 0;
|
||||||
|
qi = 0;
|
||||||
|
cno = 0;
|
||||||
|
elev = 0;
|
||||||
|
azim = 0;
|
||||||
|
}
|
||||||
|
|
||||||
type aircraft = {
|
type aircraft = {
|
||||||
id : string;
|
id : string;
|
||||||
mutable pos : Latlong.utm;
|
mutable pos : Latlong.utm;
|
||||||
@@ -93,7 +114,10 @@ type aircraft = {
|
|||||||
mutable gps_mode : int;
|
mutable gps_mode : int;
|
||||||
inflight_calib : inflight_calib;
|
inflight_calib : inflight_calib;
|
||||||
infrared : infrared;
|
infrared : infrared;
|
||||||
fbw : fbw
|
fbw : fbw;
|
||||||
|
mutable svinfo_nb_channels : int;
|
||||||
|
mutable svinfo_last_channel : int;
|
||||||
|
svinfo : svinfo array
|
||||||
}
|
}
|
||||||
|
|
||||||
(** The aircrafts store *)
|
(** The aircrafts store *)
|
||||||
@@ -193,6 +217,23 @@ let log_and_parse = fun log ac_name a msg values ->
|
|||||||
a.infrared.contrast_status <- "WAITING"
|
a.infrared.contrast_status <- "WAITING"
|
||||||
| "CALIB_CONTRAST" ->
|
| "CALIB_CONTRAST" ->
|
||||||
a.infrared.contrast_value <- ivalue "adc"
|
a.infrared.contrast_value <- ivalue "adc"
|
||||||
|
| "SETTINGS" ->
|
||||||
|
a.inflight_calib.if_val1 <- fvalue "slider_1_val";
|
||||||
|
a.inflight_calib.if_val2 <- fvalue "slider_2_val";
|
||||||
|
| "SVINFO" ->
|
||||||
|
let i = ivalue "chn" in
|
||||||
|
assert(i < Array.length a.svinfo);
|
||||||
|
a.svinfo.(i) <- {
|
||||||
|
svid = ivalue "SVID";
|
||||||
|
flags = ivalue "Flags";
|
||||||
|
qi = ivalue "QI";
|
||||||
|
cno = ivalue "CNO";
|
||||||
|
elev = ivalue "Elev";
|
||||||
|
azim = ivalue "Azim";
|
||||||
|
};
|
||||||
|
if i = 0 then
|
||||||
|
a.svinfo_nb_channels <- a.svinfo_last_channel;
|
||||||
|
a.svinfo_last_channel <- i
|
||||||
| _ -> ()
|
| _ -> ()
|
||||||
|
|
||||||
(** Callback for a message from a registered A/C *)
|
(** Callback for a message from a registered A/C *)
|
||||||
@@ -213,12 +254,14 @@ let send_cam_status = fun a ->
|
|||||||
let h = a.alt -. float (Srtm.of_utm a.pos) in
|
let h = a.alt -. float (Srtm.of_utm a.pos) in
|
||||||
let east = a.pos.utm_x +. h *. tan (a.cam.phi -. a.roll)
|
let east = a.pos.utm_x +. h *. tan (a.cam.phi -. a.roll)
|
||||||
and north = a.pos.utm_y +. h *. tan (a.cam.theta +. a.pitch) in
|
and north = a.pos.utm_y +. h *. tan (a.cam.theta +. a.pitch) in
|
||||||
let values = ["east", Pprz.Float east; "north", Pprz.Float north] in
|
let values = ["cam_east", Pprz.Float east; "cam_north", Pprz.Float north] in
|
||||||
Ground_Pprz.message_send my_id "CAM_STATUS" values
|
Ground_Pprz.message_send my_id "CAM_STATUS" values
|
||||||
|
|
||||||
let send_if_calib = fun a ->
|
let send_if_calib = fun a ->
|
||||||
let values = ["ac_id", Pprz.String a.id;
|
let values = ["ac_id", Pprz.String a.id;
|
||||||
"mode", Pprz.Int a.inflight_calib.if_mode] in
|
"if_mode", Pprz.Int a.inflight_calib.if_mode;
|
||||||
|
"if_value1", Pprz.Float a.inflight_calib.if_val1;
|
||||||
|
"if_value2", Pprz.Float a.inflight_calib.if_val2] in
|
||||||
Ground_Pprz.message_send my_id "INFLIGH_CALIB" values
|
Ground_Pprz.message_send my_id "INFLIGH_CALIB" values
|
||||||
|
|
||||||
let send_fbw = fun a ->
|
let send_fbw = fun a ->
|
||||||
@@ -236,6 +279,30 @@ let send_infrared = fun a ->
|
|||||||
] in
|
] in
|
||||||
Ground_Pprz.message_send my_id "INFRARED" values
|
Ground_Pprz.message_send my_id "INFRARED" values
|
||||||
|
|
||||||
|
let send_svsinfo = fun a ->
|
||||||
|
if a.svinfo_last_channel = 0 then begin
|
||||||
|
let svid = ref ","
|
||||||
|
and flags= ref ","
|
||||||
|
and qi = ref ","
|
||||||
|
and cno = ref ","
|
||||||
|
and elev = ref ","
|
||||||
|
and azim = ref "," in
|
||||||
|
for i = 0 to a.svinfo_nb_channels - 1 do
|
||||||
|
let concat = fun ref v ->
|
||||||
|
ref := !ref ^ string_of_int v ^ "," in
|
||||||
|
concat svid a.svinfo.(i).svid;
|
||||||
|
concat flags a.svinfo.(i).flags;
|
||||||
|
concat qi a.svinfo.(i).qi;
|
||||||
|
concat cno a.svinfo.(i).cno;
|
||||||
|
concat elev a.svinfo.(i).elev;
|
||||||
|
concat azim a.svinfo.(i).azim
|
||||||
|
done;
|
||||||
|
let f = fun s r -> (s, Pprz.String !r) in
|
||||||
|
let vs = [f "SVID" svid; f "Flags" flags; f "QI" qi;
|
||||||
|
f "CNO" cno; f "Elev" elev; f "Azim" azim] in
|
||||||
|
Ground_Pprz.message_send my_id "SVSINFO" vs
|
||||||
|
end
|
||||||
|
|
||||||
|
|
||||||
let send_aircraft_msg = fun ac ->
|
let send_aircraft_msg = fun ac ->
|
||||||
try
|
try
|
||||||
@@ -270,7 +337,7 @@ let send_aircraft_msg = fun ac ->
|
|||||||
Ground_Pprz.message_send my_id "ENGINE_STATUS" values;
|
Ground_Pprz.message_send my_id "ENGINE_STATUS" values;
|
||||||
|
|
||||||
let values = ["ac_id", Pprz.String ac;
|
let values = ["ac_id", Pprz.String ac;
|
||||||
"mode", Pprz.Int a.ap_mode;
|
"ap_mode", Pprz.Int a.ap_mode;
|
||||||
"v_mode", Pprz.Int a.ap_altitude;
|
"v_mode", Pprz.Int a.ap_altitude;
|
||||||
"gps_mode", Pprz.Int a.gps_mode] in
|
"gps_mode", Pprz.Int a.gps_mode] in
|
||||||
Ground_Pprz.message_send my_id "AP_STATUS" values;
|
Ground_Pprz.message_send my_id "AP_STATUS" values;
|
||||||
@@ -287,9 +354,12 @@ let new_aircraft = fun id ->
|
|||||||
{ id = id ; roll = 0.; pitch = 0.; nav_ref_east = 0.; nav_ref_north = 0.; desired_east = 0.; desired_north = 0.; gspeed=0.; course = 0.; alt=0.; climb=0.; cur_block=0; cur_stage=0; throttle = 0.; rpm = 0.; temp = 0.; bat = 0.; amp = 0.; energy = 0.; ap_mode=0; ap_altitude=0; gps_mode =0;
|
{ id = id ; roll = 0.; pitch = 0.; nav_ref_east = 0.; nav_ref_north = 0.; desired_east = 0.; desired_north = 0.; gspeed=0.; course = 0.; alt=0.; climb=0.; cur_block=0; cur_stage=0; throttle = 0.; rpm = 0.; temp = 0.; bat = 0.; amp = 0.; energy = 0.; ap_mode=0; ap_altitude=0; gps_mode =0;
|
||||||
pos = { utm_x = 0.; utm_y = 0.; utm_zone = 0 };
|
pos = { utm_x = 0.; utm_y = 0.; utm_zone = 0 };
|
||||||
cam = { phi = 0.; theta = 0. };
|
cam = { phi = 0.; theta = 0. };
|
||||||
inflight_calib = { if_mode = 1 };
|
inflight_calib = { if_mode = 1 ; if_val1 = 0.; if_val2 = 0.};
|
||||||
infrared = infrared_init;
|
infrared = infrared_init;
|
||||||
fbw = { rc_status = "???"; rc_mode = "???" }
|
fbw = { rc_status = "???"; rc_mode = "???" };
|
||||||
|
svinfo_nb_channels = 0;
|
||||||
|
svinfo_last_channel = -1;
|
||||||
|
svinfo = Array.create gps_nb_channels svinfo_init
|
||||||
}
|
}
|
||||||
|
|
||||||
let register_aircraft = fun name a ->
|
let register_aircraft = fun name a ->
|
||||||
|
|||||||
Reference in New Issue
Block a user