diff --git a/CHANGELOGS.md b/CHANGELOGS.md index 4c663bf59..696b10f1f 100644 --- a/CHANGELOGS.md +++ b/CHANGELOGS.md @@ -1,5 +1,13 @@ dragonpilot [latest] - EON/C2 Release ======================== +* NEW: Synced to openpilot master 2022.08.29 commits. + * Nuclear Grade driving model. +* TWEAK: Used fused location service on mapd. +* TWEAK: Used fused location service on gpxd. +* NEW: Added back auto boot on C2. + +dragonpilot 2022.08.29 - EON/C2 Release +======================== * NEW: Synced to openpilot master 2022.08.23 commits. * New driving model. * NEW: Added back honda eps mod toggle. diff --git a/README.md b/README.md index 0b6fc2010..c2c90b0e6 100755 --- a/README.md +++ b/README.md @@ -42,7 +42,7 @@ To use openpilot in a car, you need four things * A supported device to run this software: a [comma three](https://comma.ai/shop/products/three). * This software. The setup procedure of the comma three allows the user to enter a URL for custom software. The URL, openpilot.comma.ai will install the release version of openpilot. To install openpilot master, you can use installer.comma.ai/commaai/master, and replacing commaai with another GitHub username can install a fork. -* One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. +* One of [the 200+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported but has adaptive cruise control and lane-keeping assist, it's likely able to run openpilot. * A [car harness](https://comma.ai/shop/products/car-harness) to connect to your car. We have detailed instructions for [how to mount the device in a car](https://comma.ai/setup). diff --git a/RELEASES.md b/RELEASES.md index 3ac6c8e41..28a010968 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,5 +1,7 @@ Version 0.8.17 (2022-XX-XX) ======================== +* New driving model + * Internal feature space accuracy increased tenfold during training, this makes the model dramatically more accurate. Version 0.8.16 (2022-08-26) ======================== diff --git a/cereal/car.capnp b/cereal/car.capnp index 2fc8227c3..7115cc3c3 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -470,7 +470,7 @@ struct CarParams { vEgoStarting @59 :Float32; # Speed at which the car goes into starting state directAccelControl @30 :Bool; # Does the car have direct accel control or just gas/brake stoppingControl @31 :Bool; # Does the car allows full control even at lows speeds when stopping - stopAccel @60 :Float32; # Required acceleraton to keep vehicle stationary + stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary steerControlType @34 :SteerControlType; radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop @@ -585,8 +585,8 @@ struct CarParams { subaruLegacy @22; # pre-Global platform hyundaiLegacy @23; hyundaiCommunity @24; - stellantis @25; - faw @26; + stellantisDEPRECATED @25; # Consolidated with Chrysler; may be recycled for the next new model + hongqi @26; body @27; hyundaiCanfd @28; } diff --git a/cereal/libcereal_shared.so b/cereal/libcereal_shared.so index 83884e295..032c67022 100755 Binary files a/cereal/libcereal_shared.so and b/cereal/libcereal_shared.so differ diff --git a/cereal/log.capnp b/cereal/log.capnp index 5d395f9f7..d0dd3f94e 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -1238,7 +1238,7 @@ struct UbloxGnss { carrierPhaseValid @1 :Bool; # half cycle valid halfCycleValid @2 :Bool; - # half sycle subtracted from phase + # half cycle subtracted from phase halfCycleSubtracted @3 :Bool; } } diff --git a/cereal/visionipc/visionipc_pyx.so b/cereal/visionipc/visionipc_pyx.so index 353af5bae..19190c9f2 100755 Binary files a/cereal/visionipc/visionipc_pyx.so and b/cereal/visionipc/visionipc_pyx.so differ diff --git a/common/params_pyx.cpp b/common/params_pyx.cpp index ad69ae8aa..a84118979 100644 --- a/common/params_pyx.cpp +++ b/common/params_pyx.cpp @@ -1720,7 +1720,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_8get(struct __pyx_obj_6co static PyObject *__pyx_pf_6common_10params_pyx_6Params_10get_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ static PyObject *__pyx_pf_6common_10params_pyx_6Params_12put(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat); /* proto */ static PyObject *__pyx_pf_6common_10params_pyx_6Params_14put_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val); /* proto */ -static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ static PyObject *__pyx_pf_6common_10params_pyx_6Params_18get_param_path(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ static PyObject *__pyx_pf_6common_10params_pyx_6Params_20__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ static PyObject *__pyx_pf_6common_10params_pyx_6Params_22__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ @@ -3114,7 +3114,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_14put_bool(struct __pyx_o * with nogil: * self.p.putBool(k, val) # <<<<<<<<<<<<<< * - * def delete(self, key): + * def remove(self, key): */ (void)(__pyx_v_self->p->putBool(__pyx_v_k, __pyx_v_val)); } @@ -3164,25 +3164,25 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_14put_bool(struct __pyx_o /* "common/params_pyx.pyx":93 * self.p.putBool(k, val) * - * def delete(self, key): # <<<<<<<<<<<<<< + * def remove(self, key): # <<<<<<<<<<<<<< * cdef string k = self.check_key(key) * with nogil: */ /* Python wrapper */ -static PyObject *__pyx_pw_6common_10params_pyx_6Params_17delete(PyObject *__pyx_v_self, PyObject *__pyx_v_key); /*proto*/ -static PyObject *__pyx_pw_6common_10params_pyx_6Params_17delete(PyObject *__pyx_v_self, PyObject *__pyx_v_key) { +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17remove(PyObject *__pyx_v_self, PyObject *__pyx_v_key); /*proto*/ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17remove(PyObject *__pyx_v_self, PyObject *__pyx_v_key) { PyObject *__pyx_r = 0; __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("delete (wrapper)", 0); - __pyx_r = __pyx_pf_6common_10params_pyx_6Params_16delete(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), ((PyObject *)__pyx_v_key)); + __Pyx_RefNannySetupContext("remove (wrapper)", 0); + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_16remove(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), ((PyObject *)__pyx_v_key)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { std::string __pyx_v_k; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -3193,11 +3193,11 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("delete", 0); + __Pyx_RefNannySetupContext("remove", 0); /* "common/params_pyx.pyx":94 * - * def delete(self, key): + * def remove(self, key): * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< * with nogil: * self.p.remove(k) @@ -3224,7 +3224,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj __pyx_v_k = __pyx_t_4; /* "common/params_pyx.pyx":95 - * def delete(self, key): + * def remove(self, key): * cdef string k = self.check_key(key) * with nogil: # <<<<<<<<<<<<<< * self.p.remove(k) @@ -3249,7 +3249,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj } /* "common/params_pyx.pyx":95 - * def delete(self, key): + * def remove(self, key): * cdef string k = self.check_key(key) * with nogil: # <<<<<<<<<<<<<< * self.p.remove(k) @@ -3270,7 +3270,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj /* "common/params_pyx.pyx":93 * self.p.putBool(k, val) * - * def delete(self, key): # <<<<<<<<<<<<<< + * def remove(self, key): # <<<<<<<<<<<<<< * cdef string k = self.check_key(key) * with nogil: */ @@ -3282,7 +3282,7 @@ static PyObject *__pyx_pf_6common_10params_pyx_6Params_16delete(struct __pyx_obj __Pyx_XDECREF(__pyx_t_1); __Pyx_XDECREF(__pyx_t_2); __Pyx_XDECREF(__pyx_t_3); - __Pyx_AddTraceback("common.params_pyx.Params.delete", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_AddTraceback("common.params_pyx.Params.remove", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; __Pyx_XGIVEREF(__pyx_r); @@ -6060,7 +6060,7 @@ static PyMethodDef __pyx_methods_6common_10params_pyx_Params[] = { {"get_bool", (PyCFunction)__pyx_pw_6common_10params_pyx_6Params_11get_bool, METH_O, 0}, {"put", (PyCFunction)(void*)(PyCFunctionWithKeywords)__pyx_pw_6common_10params_pyx_6Params_13put, METH_VARARGS|METH_KEYWORDS, __pyx_doc_6common_10params_pyx_6Params_12put}, {"put_bool", (PyCFunction)(void*)(PyCFunctionWithKeywords)__pyx_pw_6common_10params_pyx_6Params_15put_bool, METH_VARARGS|METH_KEYWORDS, 0}, - {"delete", (PyCFunction)__pyx_pw_6common_10params_pyx_6Params_17delete, METH_O, 0}, + {"remove", (PyCFunction)__pyx_pw_6common_10params_pyx_6Params_17remove, METH_O, 0}, {"get_param_path", (PyCFunction)(void*)(PyCFunctionWithKeywords)__pyx_pw_6common_10params_pyx_6Params_19get_param_path, METH_VARARGS|METH_KEYWORDS, 0}, {"__reduce_cython__", (PyCFunction)__pyx_pw_6common_10params_pyx_6Params_21__reduce_cython__, METH_NOARGS, 0}, {"__setstate_cython__", (PyCFunction)__pyx_pw_6common_10params_pyx_6Params_23__setstate_cython__, METH_O, 0}, diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 36c8cf777..8d52b8d3f 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -90,7 +90,7 @@ cdef class Params: with nogil: self.p.putBool(k, val) - def delete(self, key): + def remove(self, key): cdef string k = self.check_key(key) with nogil: self.p.remove(k) diff --git a/common/params_pyx.so b/common/params_pyx.so index b3d93150e..b5e6d28d4 100755 Binary files a/common/params_pyx.so and b/common/params_pyx.so differ diff --git a/common/version.h b/common/version.h index 51848d91b..281df34d8 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "2022.08.26" +#define COMMA_VERSION "2022.08.30" diff --git a/opendbc/can/libdbc.so b/opendbc/can/libdbc.so index 29d20a2d6..0880d11e7 100755 Binary files a/opendbc/can/libdbc.so and b/opendbc/can/libdbc.so differ diff --git a/opendbc/vw_golf_mk4.dbc b/opendbc/vw_golf_mk4.dbc index 39d518df4..b266a7f4c 100644 --- a/opendbc/vw_golf_mk4.dbc +++ b/opendbc/vw_golf_mk4.dbc @@ -296,7 +296,9 @@ BO_ 1408 Motor_Flexia: 8 XXX SG_ Verschleissindex : 16|8@1+ (1,0) [0|254] "" XXX SG_ Russindex : 8|8@1+ (1,0) [0|254] "" XXX SG_ Verbrennungsart : 7|1@1+ (1,0) [0|0] "" XXX - SG_ Frei_Motor_Flexia_1 : 4|3@1+ (1,0) [0|0] "" XXX + SG_ Frei_Motor_Flexia_1 : 6|1@1+ (1,0) [0|0] "" XXX + SG_ Warm_Up_Cycle : 5|1@1+ (1,0) [0|0] "" XXX + SG_ Driving_Cycle : 4|1@1+ (1,0) [0|0] "" XXX SG_ Zaehler_Motor_Flexia : 1|3@1+ (1,0) [0|15] "" XXX SG_ Multiplex_Schalter_Motor_Flexia M : 0|1@1+ (1,0) [0|0] "" XXX @@ -1457,19 +1459,28 @@ CM_ SG_ 640 Fahrerwunschmoment "Driver Requested Torque"; CM_ SG_ 640 mechanisches_Motor_Verlustmomen "Mechanical Torque Loss"; CM_ SG_ 640 Fahrpedalwert_oder_Drosselklapp "Accelerator Pedal or Throttle Position"; CM_ SG_ 640 Motordrehzahl "Engine Speed"; +CM_ SG_ 640 Momentenangaben_ungenau "Approximate Torque Values"; CM_ SG_ 644 MOB_CHECKSUM "Checksum MOB"; CM_ SG_ 644 MOB_COUNTER "Counter MOB"; +CM_ SG_ 648 Minimales_Motormoment_bei_Zuend "Minimum Torque Adjustment"; +CM_ SG_ 648 Begrenzungsmoment "Maximum Inner Torque"; CM_ SG_ 648 Bremstestschalter "Brake Test Switch"; +CM_ SG_ 648 Soll_Geschwindigkeit_bei_GRA_Be "Desired Vehicle Speed"; CM_ SG_ 648 Bremslichtschalter "Brake Light Switch"; CM_ SG_ 648 Leerlaufsolldrehzahl__Motor_2_ "Target Idle Speed"; CM_ SG_ 648 Fahrzeuggeschwindigkeit "Vehicle Speed"; CM_ SG_ 648 Kuehlmitteltemperatur__Motor_2_ "Coolant Temperature"; CM_ SG_ 896 Drosselklappenpoti "Throttle Position"; +CM_ SG_ 896 Motor_Wunschdrehzahl "Desired engine speed"; +CM_ SG_ 896 Motordrehzahlbeeinflussung "Shift Target Influence"; CM_ SG_ 896 Fahrpedal_Rohsignal "Accelerator Pedal Position"; CM_ SG_ 896 Ansauglufttemperatur "Intake Air Temperature"; +CM_ SG_ 896 Kein_E_Gas "ETB flag"; +CM_ SG_ 896 Kein_Start_Stop "Start/stop flag"; +CM_ SG_ 896 Rad_Wunschmoment "Desired wheel torque"; CM_ SG_ 912 GK1_Fa_Tuerkont "Status of the driver's door rotary latch"; CM_ SG_ 912 BSK_HL_geoeffnet "Status of the rear left door rotary latch"; @@ -1480,6 +1491,15 @@ CM_ SG_ 912 BSK_HD_Hauptraste "Status of trunk lid main detent"; CM_ SG_ 1088 Zaehler_Getriebe_1 "Counter Getriebe_1"; CM_ SG_ 1088 Waehlhebelposition__Getriebe_1_ "Gear Selector Position"; +CM_ SG_ 1056 Fehlerstatus_Aussentemp__4_1 "ambient temp error"; +CM_ SG_ 1056 Fehlerstatus_Oeltemperatur_4_1 "oil temp error"; +CM_ SG_ 1056 Fehlerst__Kuehlmitteltemp__4_1 "water temp error"; +CM_ SG_ 1056 Aussentemperatur_gefiltert "outside temp, filtered"; +CM_ SG_ 1056 Oeltemperatur_4_1 "kombi oil temperature"; +CM_ SG_ 1056 Kuehlmitteltemp__4_1__Kombi_2_ "kombi coolant temperature"; + +CM_ SG_ 1096 Zaehler_Waehlhebel_1 "Counter Waehlhebel_1"; + CM_ SG_ 1152 Checksumme_Motor_5 "Checksum Motor_5"; CM_ SG_ 1160 Zaehler_Motor_6 "Counter Motor_6"; @@ -1492,6 +1512,16 @@ CM_ SG_ 1344 Zahler_Getriebe_2 "Counter Getriebe_2"; CM_ SG_ 1386 ACA_V_Wunsch "255=unset"; +CM_ SG_ 1408 Zaehler_Motor_Flexia "Counter Motor_Flexia"; +CM_ SG_ 1408 Verbrennungsart "Type of combustion"; +CM_ SG_ 1408 Max_Drehmoment "Maximum torque"; +CM_ SG_ 1408 Drehzahl_MaxNorm "RPM of maximum torque"; +CM_ SG_ 1408 Hubraum "Displacement"; +CM_ SG_ 1408 Anzahl_Zylinder "Number of cylinders"; +CM_ SG_ 1408 Anzahl_Ventile "Number of valves"; +CM_ SG_ 1408 Ansaugsystem "Induction System"; +CM_ SG_ 1408 Motorleistung "Maximum engine power"; + CM_ SG_ 1416 Ladedruck "Boost Pressure"; CM_ SG_ 1470 LDW_Direction "0=right,1=left"; diff --git a/panda/board/obj/bootstub.panda.bin b/panda/board/obj/bootstub.panda.bin index 5e813c10d..8c0beadab 100755 Binary files a/panda/board/obj/bootstub.panda.bin and b/panda/board/obj/bootstub.panda.bin differ diff --git a/panda/board/obj/panda.bin.signed b/panda/board/obj/panda.bin.signed index f11590344..5cb95806e 100644 Binary files a/panda/board/obj/panda.bin.signed and b/panda/board/obj/panda.bin.signed differ diff --git a/panda/board/obj/panda.bin.sspoof.signed b/panda/board/obj/panda.bin.sspoof.signed index 7d8ba5b93..b388504c4 100644 Binary files a/panda/board/obj/panda.bin.sspoof.signed and b/panda/board/obj/panda.bin.sspoof.signed differ diff --git a/panda/board/obj/panda.bin.testing.signed b/panda/board/obj/panda.bin.testing.signed index ce026165b..2df7d398d 100644 Binary files a/panda/board/obj/panda.bin.testing.signed and b/panda/board/obj/panda.bin.testing.signed differ diff --git a/panda/board/obj/panda.bin.testing.sspoof.signed b/panda/board/obj/panda.bin.testing.sspoof.signed index 41bf7018b..3a6dfc9d3 100644 Binary files a/panda/board/obj/panda.bin.testing.sspoof.signed and b/panda/board/obj/panda.bin.testing.sspoof.signed differ diff --git a/panda/python/__init__.py b/panda/python/__init__.py index de382f384..e06cf0ba1 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -1,12 +1,13 @@ # python library to interface with panda -import datetime +import os +import sys +import time +import usb1 import struct import hashlib -import usb1 -import os -import time +import datetime import traceback -import sys +import warnings from functools import wraps from typing import Optional from itertools import accumulate @@ -410,7 +411,11 @@ class Panda: for device in context.getDeviceList(skip_on_error=True): if device.getVendorID() == 0xbbaa and device.getProductID() in (0xddcc, 0xddee): try: - ret.append(device.getSerialNumber()) + serial = device.getSerialNumber() + if len(serial) == 24: + ret.append(serial) + else: + warnings.warn(f"found device with panda descriptors but invalid serial: {serial}", RuntimeWarning) except Exception: continue except Exception: diff --git a/rednose/helpers/ekf_sym_pyx.so b/rednose/helpers/ekf_sym_pyx.so index 65a9827b4..c3710c26d 100755 Binary files a/rednose/helpers/ekf_sym_pyx.so and b/rednose/helpers/ekf_sym_pyx.so differ diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 321bc274e..f4ec8a81a 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -740,14 +740,14 @@ def main(): break except (ConnectionError, TimeoutError, WebSocketException): conn_retries += 1 - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") except socket.timeout: - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") except Exception: cloudlog.exception("athenad.main.exception") conn_retries += 1 - params.delete("LastAthenaPingTime") + params.remove("LastAthenaPingTime") time.sleep(backoff(conn_retries)) diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index 6bbb03a79..59ca2430c 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -27,7 +27,7 @@ def main(): except Exception: cloudlog.exception("manage_athenad.exception") finally: - params.delete(ATHENA_MGR_PID_PARAM) + params.remove(ATHENA_MGR_PID_PARAM) if __name__ == '__main__': diff --git a/selfdrive/boardd/boardd b/selfdrive/boardd/boardd index 3f21128b8..f66b5adbc 100755 Binary files a/selfdrive/boardd/boardd and b/selfdrive/boardd/boardd differ diff --git a/selfdrive/boardd/boardd_api_impl.so b/selfdrive/boardd/boardd_api_impl.so index aa872a992..56dfc75c9 100755 Binary files a/selfdrive/boardd/boardd_api_impl.so and b/selfdrive/boardd/boardd_api_impl.so differ diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 54a28a678..971756002 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -83,7 +83,7 @@ def main() -> NoReturn: while True: try: - params.delete("PandaSignatures") + params.remove("PandaSignatures") # Flash all Pandas in DFU mode for p in PandaDFU.list(): diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 10478efa8..ef5471490 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -170,6 +170,7 @@ FW_VERSIONS = { b'68448163AJ', b'68500630AD', b'68539650AD', + b'68378758AM ', ], (Ecu.transmission, 0x7e1, None): [ b'68360078AL', diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 9d2fd11b4..886bf4aff 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -97,6 +97,11 @@ CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ p16(0xf132) +CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) +CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) + CHRYSLER_RX_OFFSET = -0x280 FORD_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ @@ -208,12 +213,20 @@ REQUESTS: List[Request] = [ "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.esp, Ecu.eps, Ecu.srs, Ecu.gateway, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], rx_offset=CHRYSLER_RX_OFFSET, ), Request( "chrysler", [CHRYSLER_VERSION_REQUEST], [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + ), + Request( + "chrysler", + [CHRYSLER_SOFTWARE_VERSION_REQUEST], + [CHRYSLER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], ), # Ford Request( diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 7cd7be2df..907db5d79 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -138,28 +138,29 @@ class CarController: can_sends.append(create_gas_interceptor_command(self.packer, interceptor_gas_cmd, self.frame // 2)) self.gas = interceptor_gas_cmd - # ui mesg is at 1Hz but we send asap if: - # - there is something to display - # - there is something to stop displaying - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + if self.CP.carFingerprint != CAR.PRIUS_V: + # ui mesg is at 1Hz but we send asap if: + # - there is something to display + # - there is something to stop displaying + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - send_ui = False - if ((fcw_alert or steer_alert) and not self.alert_active) or \ - (not (fcw_alert or steer_alert) and self.alert_active): - send_ui = True - self.alert_active = not self.alert_active - elif pcm_cancel_cmd: - # forcing the pcm to disengage causes a bad fault sound so play a good sound instead - send_ui = True + send_ui = False + if ((fcw_alert or steer_alert) and not self.alert_active) or \ + (not (fcw_alert or steer_alert) and self.alert_active): + send_ui = True + self.alert_active = not self.alert_active + elif pcm_cancel_cmd: + # forcing the pcm to disengage causes a bad fault sound so play a good sound instead + send_ui = True - if (self.frame % 100 == 0 or send_ui) and (self.CP.carFingerprint != CAR.PRIUS_V): - can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, - hud_control.rightLaneVisible, hud_control.leftLaneDepart, - hud_control.rightLaneDepart, CC.enabled)) + if self.frame % 100 == 0 or send_ui: + can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leftLaneDepart, + hud_control.rightLaneDepart, CC.enabled)) - if (self.frame % 100 == 0 or send_ui) and self.CP.enableDsu: - can_sends.append(create_fcw_command(self.packer, fcw_alert)) + if (self.frame % 100 == 0 or send_ui) and self.CP.enableDsu: + can_sends.append(create_fcw_command(self.packer, fcw_alert)) # *** static msgs *** for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index ed02848f7..bf648424d 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1268,6 +1268,7 @@ FW_VERSIONS = { b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'\x01F15260R210\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 58f071901..954b7060c 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -369,6 +369,7 @@ FW_VERSIONS = { b'\xf1\x870D9300012 \xf1\x894937', b'\xf1\x870D9300012 \xf1\x895045', b'\xf1\x870D9300014M \xf1\x895004', + b'\xf1\x870D9300014Q \xf1\x895006', b'\xf1\x870D9300020S \xf1\x895201', b'\xf1\x870D9300040A \xf1\x893613', b'\xf1\x870D9300040S \xf1\x894311', diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 3cb7b95b8..b8da7411f 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -177,14 +177,14 @@ class Controls: self.state = State.disabled self.enabled = False self.active = False - self.can_rcv_error = False + self.can_rcv_timeout = False self.soft_disable_timer = 0 self.v_cruise_kph = V_CRUISE_INITIAL self.v_cruise_cluster_kph = V_CRUISE_INITIAL self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 - self.can_rcv_error_counter = 0 + self.can_rcv_timeout_counter = 0 self.last_blinker_frame = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 @@ -356,19 +356,19 @@ class Controls: # generic catch-all. ideally, a more specific event should be added above instead has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any(ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE)) no_system_errors = (not has_disable_events) or (len(self.events) == num_events) - if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors: + if (not self.sm.all_checks() or self.can_rcv_timeout) and no_system_errors: if not self.sm.all_alive(): self.events.add(EventName.commIssue) elif not self.sm.all_freq_ok(): self.events.add(EventName.commIssueAvgFreq) - else: # invalid or can_rcv_error. + else: # invalid or can_rcv_timeout. self.events.add(EventName.commIssue) logs = { 'invalid': [s for s, valid in self.sm.valid.items() if not valid], 'not_alive': [s for s, alive in self.sm.alive.items() if not alive], 'not_freq_ok': [s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok], - 'can_error': self.can_rcv_error, + 'can_rcv_timeout': self.can_rcv_timeout, } if logs != self.logged_comm_issue: cloudlog.event("commIssue", error=True, **logs) @@ -459,10 +459,10 @@ class Controls: # Check for CAN timeout if not can_strs: - self.can_rcv_error_counter += 1 - self.can_rcv_error = True + self.can_rcv_timeout_counter += 1 + self.can_rcv_timeout = True else: - self.can_rcv_error = False + self.can_rcv_timeout = False # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through @@ -814,7 +814,7 @@ class Controls: controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) - controlsState.canErrorCounter = self.can_rcv_error_counter + controlsState.canErrorCounter = self.can_rcv_timeout_counter lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index 2dad05e21..cb878483d 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -22,7 +22,7 @@ def set_offroad_alert(alert: str, show_alert: bool, extra_text: Optional[str] = a['text'] += extra_text Params().put(alert, json.dumps(a)) else: - Params().delete(alert) + Params().remove(alert) @dataclass diff --git a/selfdrive/dragonpilot/gpxd.py b/selfdrive/dragonpilot/gpxd.py index 1fd364a24..5bd37488e 100644 --- a/selfdrive/dragonpilot/gpxd.py +++ b/selfdrive/dragonpilot/gpxd.py @@ -28,17 +28,30 @@ import datetime import signal import threading from common.realtime import Ratekeeper +import math +from cereal import log +from system.swaglog import cloudlog # customisable values GPX_LOG_PATH = '/data/media/0/gpx_logs/' LOG_HERTZ = 10 # 10 hz = 0.1 sec, higher for higher accuracy, 10hz seems fine LOG_LENGTH = 10 # mins, higher means it keeps more data in the memory, will take more time to write into a file too. -LOST_SIGNAL_COUNT_LENGTH = 30 # secs, output log file if we lost signal for this long +LOST_SIGNAL_COUNT_LENGTH = 10 # secs, output log file if we lost signal for this long # do not change LOST_SIGNAL_COUNT_MAX = LOST_SIGNAL_COUNT_LENGTH * LOG_HERTZ # secs, LOGS_PER_FILE = LOG_LENGTH * 60 * LOG_HERTZ # e.g. 10 * 60 * 10 = 6000 points per file +_DEBUG = False +_CLOUDLOG_DEBUG = True + + +def _debug(msg, log_to_cloud=True): + if _CLOUDLOG_DEBUG and log_to_cloud: + cloudlog.debug(msg) + if _DEBUG: + print(msg) + class WaitTimeHelper: ready_event = threading.Event() shutdown = False @@ -60,27 +73,33 @@ class GpxD(): self.wait_helper = WaitTimeHelper() self.started_time = datetime.datetime.utcnow().isoformat() self.v_ego_prev = 0. - self.pause = False + self.pause = True def log(self, sm): + location = sm['liveLocationKalman'] gps = sm['gpsLocationExternal'] v_ego = sm['carState'].vEgo if abs(v_ego) > 0.01: self.pause = False - # do not log when no fix or accuracy is too low, add lost_signal_count - if gps.flags % 2 == 0 or gps.accuracy > 5.: + location_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid + _debug("gpxd: location_valid - %s" % location_valid) + if not location_valid or self.pause: if self.log_count > 0: self.lost_signal_count += 1 - elif self.pause: - pass else: - self.logs.append([datetime.datetime.utcfromtimestamp(gps.unixTimestampMillis*0.001).isoformat(), str(gps.latitude), str(gps.longitude), str(gps.altitude)]) + lat = location.positionGeodetic.value[0] + lon = location.positionGeodetic.value[1] + alt = gps.altitude + + _debug("gpxd: logged - %s %s %s %s" % (datetime.datetime.utcfromtimestamp(location.unixTimestampMillis*0.001).isoformat(), str(lat), str(lon), str(alt))) + self.logs.append([datetime.datetime.utcfromtimestamp(location.unixTimestampMillis*0.001).isoformat(), str(lat), str(lon), str(alt)]) self.log_count += 1 self.lost_signal_count = 0 - if abs(v_ego) < 0.01 and abs(self.v_ego_prev) > 0.: + if not self.pause and abs(v_ego) < 0.01: + _debug("gpxd: paused") self.pause = True self.v_ego_prev = v_ego @@ -90,6 +109,7 @@ class GpxD(): return if force or (self.log_count >= LOGS_PER_FILE or self.lost_signal_count >= LOST_SIGNAL_COUNT_MAX): + _debug("gpxd: save to log") self._write_gpx() self.lost_signal_count = 0 self.log_count = 0 @@ -129,7 +149,7 @@ class GpxD(): def gpxd_thread(sm=None, pm=None): if sm is None: - sm = messaging.SubMaster(['gpsLocationExternal', 'carState']) + sm = messaging.SubMaster(['liveLocationKalman', 'gpsLocationExternal', 'carState']) wait_helper = WaitTimeHelper() gpxd = GpxD() diff --git a/selfdrive/locationd/locationd b/selfdrive/locationd/locationd index 054e95d88..7700a2090 100755 Binary files a/selfdrive/locationd/locationd and b/selfdrive/locationd/locationd differ diff --git a/selfdrive/locationd/models/generated/car.cpp b/selfdrive/locationd/models/generated/car.cpp index ca5705b5f..0c4851b09 100644 --- a/selfdrive/locationd/models/generated/car.cpp +++ b/selfdrive/locationd/models/generated/car.cpp @@ -45,326 +45,326 @@ const static double MAHA_THRESH_31 = 3.8414588206941227; * * * This file is part of 'ekf' * ******************************************************************************/ -void err_fun(double *nom_x, double *delta_x, double *out_729362937437787457) { - out_729362937437787457[0] = delta_x[0] + nom_x[0]; - out_729362937437787457[1] = delta_x[1] + nom_x[1]; - out_729362937437787457[2] = delta_x[2] + nom_x[2]; - out_729362937437787457[3] = delta_x[3] + nom_x[3]; - out_729362937437787457[4] = delta_x[4] + nom_x[4]; - out_729362937437787457[5] = delta_x[5] + nom_x[5]; - out_729362937437787457[6] = delta_x[6] + nom_x[6]; - out_729362937437787457[7] = delta_x[7] + nom_x[7]; - out_729362937437787457[8] = delta_x[8] + nom_x[8]; +void err_fun(double *nom_x, double *delta_x, double *out_6258559787192254109) { + out_6258559787192254109[0] = delta_x[0] + nom_x[0]; + out_6258559787192254109[1] = delta_x[1] + nom_x[1]; + out_6258559787192254109[2] = delta_x[2] + nom_x[2]; + out_6258559787192254109[3] = delta_x[3] + nom_x[3]; + out_6258559787192254109[4] = delta_x[4] + nom_x[4]; + out_6258559787192254109[5] = delta_x[5] + nom_x[5]; + out_6258559787192254109[6] = delta_x[6] + nom_x[6]; + out_6258559787192254109[7] = delta_x[7] + nom_x[7]; + out_6258559787192254109[8] = delta_x[8] + nom_x[8]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_4929143687762803407) { - out_4929143687762803407[0] = -nom_x[0] + true_x[0]; - out_4929143687762803407[1] = -nom_x[1] + true_x[1]; - out_4929143687762803407[2] = -nom_x[2] + true_x[2]; - out_4929143687762803407[3] = -nom_x[3] + true_x[3]; - out_4929143687762803407[4] = -nom_x[4] + true_x[4]; - out_4929143687762803407[5] = -nom_x[5] + true_x[5]; - out_4929143687762803407[6] = -nom_x[6] + true_x[6]; - out_4929143687762803407[7] = -nom_x[7] + true_x[7]; - out_4929143687762803407[8] = -nom_x[8] + true_x[8]; +void inv_err_fun(double *nom_x, double *true_x, double *out_8483442434741396819) { + out_8483442434741396819[0] = -nom_x[0] + true_x[0]; + out_8483442434741396819[1] = -nom_x[1] + true_x[1]; + out_8483442434741396819[2] = -nom_x[2] + true_x[2]; + out_8483442434741396819[3] = -nom_x[3] + true_x[3]; + out_8483442434741396819[4] = -nom_x[4] + true_x[4]; + out_8483442434741396819[5] = -nom_x[5] + true_x[5]; + out_8483442434741396819[6] = -nom_x[6] + true_x[6]; + out_8483442434741396819[7] = -nom_x[7] + true_x[7]; + out_8483442434741396819[8] = -nom_x[8] + true_x[8]; } -void H_mod_fun(double *state, double *out_8315888887196402654) { - out_8315888887196402654[0] = 1.0; - out_8315888887196402654[1] = 0; - out_8315888887196402654[2] = 0; - out_8315888887196402654[3] = 0; - out_8315888887196402654[4] = 0; - out_8315888887196402654[5] = 0; - out_8315888887196402654[6] = 0; - out_8315888887196402654[7] = 0; - out_8315888887196402654[8] = 0; - out_8315888887196402654[9] = 0; - out_8315888887196402654[10] = 1.0; - out_8315888887196402654[11] = 0; - out_8315888887196402654[12] = 0; - out_8315888887196402654[13] = 0; - out_8315888887196402654[14] = 0; - out_8315888887196402654[15] = 0; - out_8315888887196402654[16] = 0; - out_8315888887196402654[17] = 0; - out_8315888887196402654[18] = 0; - out_8315888887196402654[19] = 0; - out_8315888887196402654[20] = 1.0; - out_8315888887196402654[21] = 0; - out_8315888887196402654[22] = 0; - out_8315888887196402654[23] = 0; - out_8315888887196402654[24] = 0; - out_8315888887196402654[25] = 0; - out_8315888887196402654[26] = 0; - out_8315888887196402654[27] = 0; - out_8315888887196402654[28] = 0; - out_8315888887196402654[29] = 0; - out_8315888887196402654[30] = 1.0; - out_8315888887196402654[31] = 0; - out_8315888887196402654[32] = 0; - out_8315888887196402654[33] = 0; - out_8315888887196402654[34] = 0; - out_8315888887196402654[35] = 0; - out_8315888887196402654[36] = 0; - out_8315888887196402654[37] = 0; - out_8315888887196402654[38] = 0; - out_8315888887196402654[39] = 0; - out_8315888887196402654[40] = 1.0; - out_8315888887196402654[41] = 0; - out_8315888887196402654[42] = 0; - out_8315888887196402654[43] = 0; - out_8315888887196402654[44] = 0; - out_8315888887196402654[45] = 0; - out_8315888887196402654[46] = 0; - out_8315888887196402654[47] = 0; - out_8315888887196402654[48] = 0; - out_8315888887196402654[49] = 0; - out_8315888887196402654[50] = 1.0; - out_8315888887196402654[51] = 0; - out_8315888887196402654[52] = 0; - out_8315888887196402654[53] = 0; - out_8315888887196402654[54] = 0; - out_8315888887196402654[55] = 0; - out_8315888887196402654[56] = 0; - out_8315888887196402654[57] = 0; - out_8315888887196402654[58] = 0; - out_8315888887196402654[59] = 0; - out_8315888887196402654[60] = 1.0; - out_8315888887196402654[61] = 0; - out_8315888887196402654[62] = 0; - out_8315888887196402654[63] = 0; - out_8315888887196402654[64] = 0; - out_8315888887196402654[65] = 0; - out_8315888887196402654[66] = 0; - out_8315888887196402654[67] = 0; - out_8315888887196402654[68] = 0; - out_8315888887196402654[69] = 0; - out_8315888887196402654[70] = 1.0; - out_8315888887196402654[71] = 0; - out_8315888887196402654[72] = 0; - out_8315888887196402654[73] = 0; - out_8315888887196402654[74] = 0; - out_8315888887196402654[75] = 0; - out_8315888887196402654[76] = 0; - out_8315888887196402654[77] = 0; - out_8315888887196402654[78] = 0; - out_8315888887196402654[79] = 0; - out_8315888887196402654[80] = 1.0; +void H_mod_fun(double *state, double *out_317258154932342734) { + out_317258154932342734[0] = 1.0; + out_317258154932342734[1] = 0; + out_317258154932342734[2] = 0; + out_317258154932342734[3] = 0; + out_317258154932342734[4] = 0; + out_317258154932342734[5] = 0; + out_317258154932342734[6] = 0; + out_317258154932342734[7] = 0; + out_317258154932342734[8] = 0; + out_317258154932342734[9] = 0; + out_317258154932342734[10] = 1.0; + out_317258154932342734[11] = 0; + out_317258154932342734[12] = 0; + out_317258154932342734[13] = 0; + out_317258154932342734[14] = 0; + out_317258154932342734[15] = 0; + out_317258154932342734[16] = 0; + out_317258154932342734[17] = 0; + out_317258154932342734[18] = 0; + out_317258154932342734[19] = 0; + out_317258154932342734[20] = 1.0; + out_317258154932342734[21] = 0; + out_317258154932342734[22] = 0; + out_317258154932342734[23] = 0; + out_317258154932342734[24] = 0; + out_317258154932342734[25] = 0; + out_317258154932342734[26] = 0; + out_317258154932342734[27] = 0; + out_317258154932342734[28] = 0; + out_317258154932342734[29] = 0; + out_317258154932342734[30] = 1.0; + out_317258154932342734[31] = 0; + out_317258154932342734[32] = 0; + out_317258154932342734[33] = 0; + out_317258154932342734[34] = 0; + out_317258154932342734[35] = 0; + out_317258154932342734[36] = 0; + out_317258154932342734[37] = 0; + out_317258154932342734[38] = 0; + out_317258154932342734[39] = 0; + out_317258154932342734[40] = 1.0; + out_317258154932342734[41] = 0; + out_317258154932342734[42] = 0; + out_317258154932342734[43] = 0; + out_317258154932342734[44] = 0; + out_317258154932342734[45] = 0; + out_317258154932342734[46] = 0; + out_317258154932342734[47] = 0; + out_317258154932342734[48] = 0; + out_317258154932342734[49] = 0; + out_317258154932342734[50] = 1.0; + out_317258154932342734[51] = 0; + out_317258154932342734[52] = 0; + out_317258154932342734[53] = 0; + out_317258154932342734[54] = 0; + out_317258154932342734[55] = 0; + out_317258154932342734[56] = 0; + out_317258154932342734[57] = 0; + out_317258154932342734[58] = 0; + out_317258154932342734[59] = 0; + out_317258154932342734[60] = 1.0; + out_317258154932342734[61] = 0; + out_317258154932342734[62] = 0; + out_317258154932342734[63] = 0; + out_317258154932342734[64] = 0; + out_317258154932342734[65] = 0; + out_317258154932342734[66] = 0; + out_317258154932342734[67] = 0; + out_317258154932342734[68] = 0; + out_317258154932342734[69] = 0; + out_317258154932342734[70] = 1.0; + out_317258154932342734[71] = 0; + out_317258154932342734[72] = 0; + out_317258154932342734[73] = 0; + out_317258154932342734[74] = 0; + out_317258154932342734[75] = 0; + out_317258154932342734[76] = 0; + out_317258154932342734[77] = 0; + out_317258154932342734[78] = 0; + out_317258154932342734[79] = 0; + out_317258154932342734[80] = 1.0; } -void f_fun(double *state, double dt, double *out_7554938137534762046) { - out_7554938137534762046[0] = state[0]; - out_7554938137534762046[1] = state[1]; - out_7554938137534762046[2] = state[2]; - out_7554938137534762046[3] = state[3]; - out_7554938137534762046[4] = state[4]; - out_7554938137534762046[5] = dt*((-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4]))*state[6] - 9.8000000000000007*state[8] + stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*state[1]) + (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*state[4])) + state[5]; - out_7554938137534762046[6] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*state[4])) + state[6]; - out_7554938137534762046[7] = state[7]; - out_7554938137534762046[8] = state[8]; +void f_fun(double *state, double dt, double *out_5753327761686972465) { + out_5753327761686972465[0] = state[0]; + out_5753327761686972465[1] = state[1]; + out_5753327761686972465[2] = state[2]; + out_5753327761686972465[3] = state[3]; + out_5753327761686972465[4] = state[4]; + out_5753327761686972465[5] = dt*((-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4]))*state[6] - 9.8000000000000007*state[8] + stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*state[1]) + (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*state[4])) + state[5]; + out_5753327761686972465[6] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*state[4])) + state[6]; + out_5753327761686972465[7] = state[7]; + out_5753327761686972465[8] = state[8]; } -void F_fun(double *state, double dt, double *out_6130812160595680525) { - out_6130812160595680525[0] = 1; - out_6130812160595680525[1] = 0; - out_6130812160595680525[2] = 0; - out_6130812160595680525[3] = 0; - out_6130812160595680525[4] = 0; - out_6130812160595680525[5] = 0; - out_6130812160595680525[6] = 0; - out_6130812160595680525[7] = 0; - out_6130812160595680525[8] = 0; - out_6130812160595680525[9] = 0; - out_6130812160595680525[10] = 1; - out_6130812160595680525[11] = 0; - out_6130812160595680525[12] = 0; - out_6130812160595680525[13] = 0; - out_6130812160595680525[14] = 0; - out_6130812160595680525[15] = 0; - out_6130812160595680525[16] = 0; - out_6130812160595680525[17] = 0; - out_6130812160595680525[18] = 0; - out_6130812160595680525[19] = 0; - out_6130812160595680525[20] = 1; - out_6130812160595680525[21] = 0; - out_6130812160595680525[22] = 0; - out_6130812160595680525[23] = 0; - out_6130812160595680525[24] = 0; - out_6130812160595680525[25] = 0; - out_6130812160595680525[26] = 0; - out_6130812160595680525[27] = 0; - out_6130812160595680525[28] = 0; - out_6130812160595680525[29] = 0; - out_6130812160595680525[30] = 1; - out_6130812160595680525[31] = 0; - out_6130812160595680525[32] = 0; - out_6130812160595680525[33] = 0; - out_6130812160595680525[34] = 0; - out_6130812160595680525[35] = 0; - out_6130812160595680525[36] = 0; - out_6130812160595680525[37] = 0; - out_6130812160595680525[38] = 0; - out_6130812160595680525[39] = 0; - out_6130812160595680525[40] = 1; - out_6130812160595680525[41] = 0; - out_6130812160595680525[42] = 0; - out_6130812160595680525[43] = 0; - out_6130812160595680525[44] = 0; - out_6130812160595680525[45] = dt*(stiffness_front*(-state[2] - state[3] + state[7])/(mass*state[1]) + (-stiffness_front - stiffness_rear)*state[5]/(mass*state[4]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[6]/(mass*state[4])); - out_6130812160595680525[46] = -dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*pow(state[1], 2)); - out_6130812160595680525[47] = -dt*stiffness_front*state[0]/(mass*state[1]); - out_6130812160595680525[48] = -dt*stiffness_front*state[0]/(mass*state[1]); - out_6130812160595680525[49] = dt*((-1 - (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*pow(state[4], 2)))*state[6] - (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*pow(state[4], 2))); - out_6130812160595680525[50] = dt*(-stiffness_front*state[0] - stiffness_rear*state[0])/(mass*state[4]) + 1; - out_6130812160595680525[51] = dt*(-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4])); - out_6130812160595680525[52] = dt*stiffness_front*state[0]/(mass*state[1]); - out_6130812160595680525[53] = -9.8000000000000007*dt; - out_6130812160595680525[54] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front - pow(center_to_rear, 2)*stiffness_rear)*state[6]/(rotational_inertia*state[4])); - out_6130812160595680525[55] = -center_to_front*dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*pow(state[1], 2)); - out_6130812160595680525[56] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_6130812160595680525[57] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_6130812160595680525[58] = dt*(-(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*pow(state[4], 2)) - (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*pow(state[4], 2))); - out_6130812160595680525[59] = dt*(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(rotational_inertia*state[4]); - out_6130812160595680525[60] = dt*(-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])/(rotational_inertia*state[4]) + 1; - out_6130812160595680525[61] = center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_6130812160595680525[62] = 0; - out_6130812160595680525[63] = 0; - out_6130812160595680525[64] = 0; - out_6130812160595680525[65] = 0; - out_6130812160595680525[66] = 0; - out_6130812160595680525[67] = 0; - out_6130812160595680525[68] = 0; - out_6130812160595680525[69] = 0; - out_6130812160595680525[70] = 1; - out_6130812160595680525[71] = 0; - out_6130812160595680525[72] = 0; - out_6130812160595680525[73] = 0; - out_6130812160595680525[74] = 0; - out_6130812160595680525[75] = 0; - out_6130812160595680525[76] = 0; - out_6130812160595680525[77] = 0; - out_6130812160595680525[78] = 0; - out_6130812160595680525[79] = 0; - out_6130812160595680525[80] = 1; +void F_fun(double *state, double dt, double *out_8289678864136186323) { + out_8289678864136186323[0] = 1; + out_8289678864136186323[1] = 0; + out_8289678864136186323[2] = 0; + out_8289678864136186323[3] = 0; + out_8289678864136186323[4] = 0; + out_8289678864136186323[5] = 0; + out_8289678864136186323[6] = 0; + out_8289678864136186323[7] = 0; + out_8289678864136186323[8] = 0; + out_8289678864136186323[9] = 0; + out_8289678864136186323[10] = 1; + out_8289678864136186323[11] = 0; + out_8289678864136186323[12] = 0; + out_8289678864136186323[13] = 0; + out_8289678864136186323[14] = 0; + out_8289678864136186323[15] = 0; + out_8289678864136186323[16] = 0; + out_8289678864136186323[17] = 0; + out_8289678864136186323[18] = 0; + out_8289678864136186323[19] = 0; + out_8289678864136186323[20] = 1; + out_8289678864136186323[21] = 0; + out_8289678864136186323[22] = 0; + out_8289678864136186323[23] = 0; + out_8289678864136186323[24] = 0; + out_8289678864136186323[25] = 0; + out_8289678864136186323[26] = 0; + out_8289678864136186323[27] = 0; + out_8289678864136186323[28] = 0; + out_8289678864136186323[29] = 0; + out_8289678864136186323[30] = 1; + out_8289678864136186323[31] = 0; + out_8289678864136186323[32] = 0; + out_8289678864136186323[33] = 0; + out_8289678864136186323[34] = 0; + out_8289678864136186323[35] = 0; + out_8289678864136186323[36] = 0; + out_8289678864136186323[37] = 0; + out_8289678864136186323[38] = 0; + out_8289678864136186323[39] = 0; + out_8289678864136186323[40] = 1; + out_8289678864136186323[41] = 0; + out_8289678864136186323[42] = 0; + out_8289678864136186323[43] = 0; + out_8289678864136186323[44] = 0; + out_8289678864136186323[45] = dt*(stiffness_front*(-state[2] - state[3] + state[7])/(mass*state[1]) + (-stiffness_front - stiffness_rear)*state[5]/(mass*state[4]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[6]/(mass*state[4])); + out_8289678864136186323[46] = -dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*pow(state[1], 2)); + out_8289678864136186323[47] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_8289678864136186323[48] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_8289678864136186323[49] = dt*((-1 - (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*pow(state[4], 2)))*state[6] - (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*pow(state[4], 2))); + out_8289678864136186323[50] = dt*(-stiffness_front*state[0] - stiffness_rear*state[0])/(mass*state[4]) + 1; + out_8289678864136186323[51] = dt*(-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4])); + out_8289678864136186323[52] = dt*stiffness_front*state[0]/(mass*state[1]); + out_8289678864136186323[53] = -9.8000000000000007*dt; + out_8289678864136186323[54] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front - pow(center_to_rear, 2)*stiffness_rear)*state[6]/(rotational_inertia*state[4])); + out_8289678864136186323[55] = -center_to_front*dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*pow(state[1], 2)); + out_8289678864136186323[56] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8289678864136186323[57] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8289678864136186323[58] = dt*(-(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*pow(state[4], 2)) - (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*pow(state[4], 2))); + out_8289678864136186323[59] = dt*(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(rotational_inertia*state[4]); + out_8289678864136186323[60] = dt*(-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])/(rotational_inertia*state[4]) + 1; + out_8289678864136186323[61] = center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8289678864136186323[62] = 0; + out_8289678864136186323[63] = 0; + out_8289678864136186323[64] = 0; + out_8289678864136186323[65] = 0; + out_8289678864136186323[66] = 0; + out_8289678864136186323[67] = 0; + out_8289678864136186323[68] = 0; + out_8289678864136186323[69] = 0; + out_8289678864136186323[70] = 1; + out_8289678864136186323[71] = 0; + out_8289678864136186323[72] = 0; + out_8289678864136186323[73] = 0; + out_8289678864136186323[74] = 0; + out_8289678864136186323[75] = 0; + out_8289678864136186323[76] = 0; + out_8289678864136186323[77] = 0; + out_8289678864136186323[78] = 0; + out_8289678864136186323[79] = 0; + out_8289678864136186323[80] = 1; } -void h_25(double *state, double *unused, double *out_8951477070372806105) { - out_8951477070372806105[0] = state[6]; +void h_25(double *state, double *unused, double *out_5741342572066533641) { + out_5741342572066533641[0] = state[6]; } -void H_25(double *state, double *unused, double *out_9087508506817314964) { - out_9087508506817314964[0] = 0; - out_9087508506817314964[1] = 0; - out_9087508506817314964[2] = 0; - out_9087508506817314964[3] = 0; - out_9087508506817314964[4] = 0; - out_9087508506817314964[5] = 0; - out_9087508506817314964[6] = 1; - out_9087508506817314964[7] = 0; - out_9087508506817314964[8] = 0; +void H_25(double *state, double *unused, double *out_1067105512112888160) { + out_1067105512112888160[0] = 0; + out_1067105512112888160[1] = 0; + out_1067105512112888160[2] = 0; + out_1067105512112888160[3] = 0; + out_1067105512112888160[4] = 0; + out_1067105512112888160[5] = 0; + out_1067105512112888160[6] = 1; + out_1067105512112888160[7] = 0; + out_1067105512112888160[8] = 0; } -void h_24(double *state, double *unused, double *out_4067561432286125622) { - out_4067561432286125622[0] = state[4]; - out_4067561432286125622[1] = state[5]; +void h_24(double *state, double *unused, double *out_3184705636802324409) { + out_3184705636802324409[0] = state[4]; + out_3184705636802324409[1] = state[5]; } -void H_24(double *state, double *unused, double *out_1669116873140388071) { - out_1669116873140388071[0] = 0; - out_1669116873140388071[1] = 0; - out_1669116873140388071[2] = 0; - out_1669116873140388071[3] = 0; - out_1669116873140388071[4] = 1; - out_1669116873140388071[5] = 0; - out_1669116873140388071[6] = 0; - out_1669116873140388071[7] = 0; - out_1669116873140388071[8] = 0; - out_1669116873140388071[9] = 0; - out_1669116873140388071[10] = 0; - out_1669116873140388071[11] = 0; - out_1669116873140388071[12] = 0; - out_1669116873140388071[13] = 0; - out_1669116873140388071[14] = 1; - out_1669116873140388071[15] = 0; - out_1669116873140388071[16] = 0; - out_1669116873140388071[17] = 0; +void H_24(double *state, double *unused, double *out_3679403814853620874) { + out_3679403814853620874[0] = 0; + out_3679403814853620874[1] = 0; + out_3679403814853620874[2] = 0; + out_3679403814853620874[3] = 0; + out_3679403814853620874[4] = 1; + out_3679403814853620874[5] = 0; + out_3679403814853620874[6] = 0; + out_3679403814853620874[7] = 0; + out_3679403814853620874[8] = 0; + out_3679403814853620874[9] = 0; + out_3679403814853620874[10] = 0; + out_3679403814853620874[11] = 0; + out_3679403814853620874[12] = 0; + out_3679403814853620874[13] = 0; + out_3679403814853620874[14] = 1; + out_3679403814853620874[15] = 0; + out_3679403814853620874[16] = 0; + out_3679403814853620874[17] = 0; } -void h_30(double *state, double *unused, double *out_7500845677743922938) { - out_7500845677743922938[0] = state[4]; +void h_30(double *state, double *unused, double *out_5619733767201413514) { + out_5619733767201413514[0] = state[4]; } -void H_30(double *state, double *unused, double *out_4831539236764628454) { - out_4831539236764628454[0] = 0; - out_4831539236764628454[1] = 0; - out_4831539236764628454[2] = 0; - out_4831539236764628454[3] = 0; - out_4831539236764628454[4] = 1; - out_4831539236764628454[5] = 0; - out_4831539236764628454[6] = 0; - out_4831539236764628454[7] = 0; - out_4831539236764628454[8] = 0; +void H_30(double *state, double *unused, double *out_3585438470620136787) { + out_3585438470620136787[0] = 0; + out_3585438470620136787[1] = 0; + out_3585438470620136787[2] = 0; + out_3585438470620136787[3] = 0; + out_3585438470620136787[4] = 1; + out_3585438470620136787[5] = 0; + out_3585438470620136787[6] = 0; + out_3585438470620136787[7] = 0; + out_3585438470620136787[8] = 0; } -void h_26(double *state, double *unused, double *out_8341493075156931027) { - out_8341493075156931027[0] = state[7]; +void h_26(double *state, double *unused, double *out_138251146792324442) { + out_138251146792324442[0] = state[7]; } -void H_26(double *state, double *unused, double *out_5617732248018180428) { - out_5617732248018180428[0] = 0; - out_5617732248018180428[1] = 0; - out_5617732248018180428[2] = 0; - out_5617732248018180428[3] = 0; - out_5617732248018180428[4] = 0; - out_5617732248018180428[5] = 0; - out_5617732248018180428[6] = 0; - out_5617732248018180428[7] = 1; - out_5617732248018180428[8] = 0; +void H_26(double *state, double *unused, double *out_2674397806761168064) { + out_2674397806761168064[0] = 0; + out_2674397806761168064[1] = 0; + out_2674397806761168064[2] = 0; + out_2674397806761168064[3] = 0; + out_2674397806761168064[4] = 0; + out_2674397806761168064[5] = 0; + out_2674397806761168064[6] = 0; + out_2674397806761168064[7] = 1; + out_2674397806761168064[8] = 0; } -void h_27(double *state, double *unused, double *out_5342806970691419479) { - out_5342806970691419479[0] = state[3]; +void h_27(double *state, double *unused, double *out_7703728233982172330) { + out_7703728233982172330[0] = state[3]; } -void H_27(double *state, double *unused, double *out_2656775924964203543) { - out_2656775924964203543[0] = 0; - out_2656775924964203543[1] = 0; - out_2656775924964203543[2] = 0; - out_2656775924964203543[3] = 1; - out_2656775924964203543[4] = 0; - out_2656775924964203543[5] = 0; - out_2656775924964203543[6] = 0; - out_2656775924964203543[7] = 0; - out_2656775924964203543[8] = 0; +void H_27(double *state, double *unused, double *out_5809032541804080004) { + out_5809032541804080004[0] = 0; + out_5809032541804080004[1] = 0; + out_5809032541804080004[2] = 0; + out_5809032541804080004[3] = 1; + out_5809032541804080004[4] = 0; + out_5809032541804080004[5] = 0; + out_5809032541804080004[6] = 0; + out_5809032541804080004[7] = 0; + out_5809032541804080004[8] = 0; } -void h_29(double *state, double *unused, double *out_2538465680062629706) { - out_2538465680062629706[0] = state[1]; +void h_29(double *state, double *unused, double *out_3842044757553670678) { + out_3842044757553670678[0] = state[1]; } -void H_29(double *state, double *unused, double *out_5341770581079020638) { - out_5341770581079020638[0] = 0; - out_5341770581079020638[1] = 1; - out_5341770581079020638[2] = 0; - out_5341770581079020638[3] = 0; - out_5341770581079020638[4] = 0; - out_5341770581079020638[5] = 0; - out_5341770581079020638[6] = 0; - out_5341770581079020638[7] = 0; - out_5341770581079020638[8] = 0; +void H_29(double *state, double *unused, double *out_4095669814934528971) { + out_4095669814934528971[0] = 0; + out_4095669814934528971[1] = 1; + out_4095669814934528971[2] = 0; + out_4095669814934528971[3] = 0; + out_4095669814934528971[4] = 0; + out_4095669814934528971[5] = 0; + out_4095669814934528971[6] = 0; + out_4095669814934528971[7] = 0; + out_4095669814934528971[8] = 0; } -void h_28(double *state, double *unused, double *out_572823783042442857) { - out_572823783042442857[0] = state[0]; +void h_28(double *state, double *unused, double *out_3081542204526064016) { + out_3081542204526064016[0] = state[0]; } -void H_28(double *state, double *unused, double *out_7305400852644346889) { - out_7305400852644346889[0] = 1; - out_7305400852644346889[1] = 0; - out_7305400852644346889[2] = 0; - out_7305400852644346889[3] = 0; - out_7305400852644346889[4] = 0; - out_7305400852644346889[5] = 0; - out_7305400852644346889[6] = 0; - out_7305400852644346889[7] = 0; - out_7305400852644346889[8] = 0; +void H_28(double *state, double *unused, double *out_986729202135001603) { + out_986729202135001603[0] = 1; + out_986729202135001603[1] = 0; + out_986729202135001603[2] = 0; + out_986729202135001603[3] = 0; + out_986729202135001603[4] = 0; + out_986729202135001603[5] = 0; + out_986729202135001603[6] = 0; + out_986729202135001603[7] = 0; + out_986729202135001603[8] = 0; } -void h_31(double *state, double *unused, double *out_8893848845723381957) { - out_8893848845723381957[0] = state[8]; +void h_31(double *state, double *unused, double *out_2103893043812511291) { + out_2103893043812511291[0] = state[8]; } -void H_31(double *state, double *unused, double *out_4991524145784828952) { - out_4991524145784828952[0] = 0; - out_4991524145784828952[1] = 0; - out_4991524145784828952[2] = 0; - out_4991524145784828952[3] = 0; - out_4991524145784828952[4] = 0; - out_4991524145784828952[5] = 0; - out_4991524145784828952[6] = 0; - out_4991524145784828952[7] = 0; - out_4991524145784828952[8] = 1; +void H_31(double *state, double *unused, double *out_1097751473989848588) { + out_1097751473989848588[0] = 0; + out_1097751473989848588[1] = 0; + out_1097751473989848588[2] = 0; + out_1097751473989848588[3] = 0; + out_1097751473989848588[4] = 0; + out_1097751473989848588[5] = 0; + out_1097751473989848588[6] = 0; + out_1097751473989848588[7] = 0; + out_1097751473989848588[8] = 1; } #include #include @@ -518,68 +518,68 @@ void car_update_28(double *in_x, double *in_P, double *in_z, double *in_R, doubl void car_update_31(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<1, 3, 0>(in_x, in_P, h_31, H_31, NULL, in_z, in_R, in_ea, MAHA_THRESH_31); } -void car_err_fun(double *nom_x, double *delta_x, double *out_729362937437787457) { - err_fun(nom_x, delta_x, out_729362937437787457); +void car_err_fun(double *nom_x, double *delta_x, double *out_6258559787192254109) { + err_fun(nom_x, delta_x, out_6258559787192254109); } -void car_inv_err_fun(double *nom_x, double *true_x, double *out_4929143687762803407) { - inv_err_fun(nom_x, true_x, out_4929143687762803407); +void car_inv_err_fun(double *nom_x, double *true_x, double *out_8483442434741396819) { + inv_err_fun(nom_x, true_x, out_8483442434741396819); } -void car_H_mod_fun(double *state, double *out_8315888887196402654) { - H_mod_fun(state, out_8315888887196402654); +void car_H_mod_fun(double *state, double *out_317258154932342734) { + H_mod_fun(state, out_317258154932342734); } -void car_f_fun(double *state, double dt, double *out_7554938137534762046) { - f_fun(state, dt, out_7554938137534762046); +void car_f_fun(double *state, double dt, double *out_5753327761686972465) { + f_fun(state, dt, out_5753327761686972465); } -void car_F_fun(double *state, double dt, double *out_6130812160595680525) { - F_fun(state, dt, out_6130812160595680525); +void car_F_fun(double *state, double dt, double *out_8289678864136186323) { + F_fun(state, dt, out_8289678864136186323); } -void car_h_25(double *state, double *unused, double *out_8951477070372806105) { - h_25(state, unused, out_8951477070372806105); +void car_h_25(double *state, double *unused, double *out_5741342572066533641) { + h_25(state, unused, out_5741342572066533641); } -void car_H_25(double *state, double *unused, double *out_9087508506817314964) { - H_25(state, unused, out_9087508506817314964); +void car_H_25(double *state, double *unused, double *out_1067105512112888160) { + H_25(state, unused, out_1067105512112888160); } -void car_h_24(double *state, double *unused, double *out_4067561432286125622) { - h_24(state, unused, out_4067561432286125622); +void car_h_24(double *state, double *unused, double *out_3184705636802324409) { + h_24(state, unused, out_3184705636802324409); } -void car_H_24(double *state, double *unused, double *out_1669116873140388071) { - H_24(state, unused, out_1669116873140388071); +void car_H_24(double *state, double *unused, double *out_3679403814853620874) { + H_24(state, unused, out_3679403814853620874); } -void car_h_30(double *state, double *unused, double *out_7500845677743922938) { - h_30(state, unused, out_7500845677743922938); +void car_h_30(double *state, double *unused, double *out_5619733767201413514) { + h_30(state, unused, out_5619733767201413514); } -void car_H_30(double *state, double *unused, double *out_4831539236764628454) { - H_30(state, unused, out_4831539236764628454); +void car_H_30(double *state, double *unused, double *out_3585438470620136787) { + H_30(state, unused, out_3585438470620136787); } -void car_h_26(double *state, double *unused, double *out_8341493075156931027) { - h_26(state, unused, out_8341493075156931027); +void car_h_26(double *state, double *unused, double *out_138251146792324442) { + h_26(state, unused, out_138251146792324442); } -void car_H_26(double *state, double *unused, double *out_5617732248018180428) { - H_26(state, unused, out_5617732248018180428); +void car_H_26(double *state, double *unused, double *out_2674397806761168064) { + H_26(state, unused, out_2674397806761168064); } -void car_h_27(double *state, double *unused, double *out_5342806970691419479) { - h_27(state, unused, out_5342806970691419479); +void car_h_27(double *state, double *unused, double *out_7703728233982172330) { + h_27(state, unused, out_7703728233982172330); } -void car_H_27(double *state, double *unused, double *out_2656775924964203543) { - H_27(state, unused, out_2656775924964203543); +void car_H_27(double *state, double *unused, double *out_5809032541804080004) { + H_27(state, unused, out_5809032541804080004); } -void car_h_29(double *state, double *unused, double *out_2538465680062629706) { - h_29(state, unused, out_2538465680062629706); +void car_h_29(double *state, double *unused, double *out_3842044757553670678) { + h_29(state, unused, out_3842044757553670678); } -void car_H_29(double *state, double *unused, double *out_5341770581079020638) { - H_29(state, unused, out_5341770581079020638); +void car_H_29(double *state, double *unused, double *out_4095669814934528971) { + H_29(state, unused, out_4095669814934528971); } -void car_h_28(double *state, double *unused, double *out_572823783042442857) { - h_28(state, unused, out_572823783042442857); +void car_h_28(double *state, double *unused, double *out_3081542204526064016) { + h_28(state, unused, out_3081542204526064016); } -void car_H_28(double *state, double *unused, double *out_7305400852644346889) { - H_28(state, unused, out_7305400852644346889); +void car_H_28(double *state, double *unused, double *out_986729202135001603) { + H_28(state, unused, out_986729202135001603); } -void car_h_31(double *state, double *unused, double *out_8893848845723381957) { - h_31(state, unused, out_8893848845723381957); +void car_h_31(double *state, double *unused, double *out_2103893043812511291) { + h_31(state, unused, out_2103893043812511291); } -void car_H_31(double *state, double *unused, double *out_4991524145784828952) { - H_31(state, unused, out_4991524145784828952); +void car_H_31(double *state, double *unused, double *out_1097751473989848588) { + H_31(state, unused, out_1097751473989848588); } void car_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/car.h b/selfdrive/locationd/models/generated/car.h index bbe130c12..d0374774e 100644 --- a/selfdrive/locationd/models/generated/car.h +++ b/selfdrive/locationd/models/generated/car.h @@ -9,27 +9,27 @@ void car_update_27(double *in_x, double *in_P, double *in_z, double *in_R, doubl void car_update_29(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void car_update_28(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void car_update_31(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void car_err_fun(double *nom_x, double *delta_x, double *out_729362937437787457); -void car_inv_err_fun(double *nom_x, double *true_x, double *out_4929143687762803407); -void car_H_mod_fun(double *state, double *out_8315888887196402654); -void car_f_fun(double *state, double dt, double *out_7554938137534762046); -void car_F_fun(double *state, double dt, double *out_6130812160595680525); -void car_h_25(double *state, double *unused, double *out_8951477070372806105); -void car_H_25(double *state, double *unused, double *out_9087508506817314964); -void car_h_24(double *state, double *unused, double *out_4067561432286125622); -void car_H_24(double *state, double *unused, double *out_1669116873140388071); -void car_h_30(double *state, double *unused, double *out_7500845677743922938); -void car_H_30(double *state, double *unused, double *out_4831539236764628454); -void car_h_26(double *state, double *unused, double *out_8341493075156931027); -void car_H_26(double *state, double *unused, double *out_5617732248018180428); -void car_h_27(double *state, double *unused, double *out_5342806970691419479); -void car_H_27(double *state, double *unused, double *out_2656775924964203543); -void car_h_29(double *state, double *unused, double *out_2538465680062629706); -void car_H_29(double *state, double *unused, double *out_5341770581079020638); -void car_h_28(double *state, double *unused, double *out_572823783042442857); -void car_H_28(double *state, double *unused, double *out_7305400852644346889); -void car_h_31(double *state, double *unused, double *out_8893848845723381957); -void car_H_31(double *state, double *unused, double *out_4991524145784828952); +void car_err_fun(double *nom_x, double *delta_x, double *out_6258559787192254109); +void car_inv_err_fun(double *nom_x, double *true_x, double *out_8483442434741396819); +void car_H_mod_fun(double *state, double *out_317258154932342734); +void car_f_fun(double *state, double dt, double *out_5753327761686972465); +void car_F_fun(double *state, double dt, double *out_8289678864136186323); +void car_h_25(double *state, double *unused, double *out_5741342572066533641); +void car_H_25(double *state, double *unused, double *out_1067105512112888160); +void car_h_24(double *state, double *unused, double *out_3184705636802324409); +void car_H_24(double *state, double *unused, double *out_3679403814853620874); +void car_h_30(double *state, double *unused, double *out_5619733767201413514); +void car_H_30(double *state, double *unused, double *out_3585438470620136787); +void car_h_26(double *state, double *unused, double *out_138251146792324442); +void car_H_26(double *state, double *unused, double *out_2674397806761168064); +void car_h_27(double *state, double *unused, double *out_7703728233982172330); +void car_H_27(double *state, double *unused, double *out_5809032541804080004); +void car_h_29(double *state, double *unused, double *out_3842044757553670678); +void car_H_29(double *state, double *unused, double *out_4095669814934528971); +void car_h_28(double *state, double *unused, double *out_3081542204526064016); +void car_H_28(double *state, double *unused, double *out_986729202135001603); +void car_h_31(double *state, double *unused, double *out_2103893043812511291); +void car_H_31(double *state, double *unused, double *out_1097751473989848588); void car_predict(double *in_x, double *in_P, double *in_Q, double dt); void car_set_mass(double x); void car_set_rotational_inertia(double x); diff --git a/selfdrive/locationd/models/generated/gnss.cpp b/selfdrive/locationd/models/generated/gnss.cpp index 0de005582..6fc323d4e 100644 --- a/selfdrive/locationd/models/generated/gnss.cpp +++ b/selfdrive/locationd/models/generated/gnss.cpp @@ -17,354 +17,354 @@ const static double MAHA_THRESH_21 = 3.8414588206941227; * * * This file is part of 'ekf' * ******************************************************************************/ -void err_fun(double *nom_x, double *delta_x, double *out_3985733553669045281) { - out_3985733553669045281[0] = delta_x[0] + nom_x[0]; - out_3985733553669045281[1] = delta_x[1] + nom_x[1]; - out_3985733553669045281[2] = delta_x[2] + nom_x[2]; - out_3985733553669045281[3] = delta_x[3] + nom_x[3]; - out_3985733553669045281[4] = delta_x[4] + nom_x[4]; - out_3985733553669045281[5] = delta_x[5] + nom_x[5]; - out_3985733553669045281[6] = delta_x[6] + nom_x[6]; - out_3985733553669045281[7] = delta_x[7] + nom_x[7]; - out_3985733553669045281[8] = delta_x[8] + nom_x[8]; - out_3985733553669045281[9] = delta_x[9] + nom_x[9]; - out_3985733553669045281[10] = delta_x[10] + nom_x[10]; +void err_fun(double *nom_x, double *delta_x, double *out_4640013062227700412) { + out_4640013062227700412[0] = delta_x[0] + nom_x[0]; + out_4640013062227700412[1] = delta_x[1] + nom_x[1]; + out_4640013062227700412[2] = delta_x[2] + nom_x[2]; + out_4640013062227700412[3] = delta_x[3] + nom_x[3]; + out_4640013062227700412[4] = delta_x[4] + nom_x[4]; + out_4640013062227700412[5] = delta_x[5] + nom_x[5]; + out_4640013062227700412[6] = delta_x[6] + nom_x[6]; + out_4640013062227700412[7] = delta_x[7] + nom_x[7]; + out_4640013062227700412[8] = delta_x[8] + nom_x[8]; + out_4640013062227700412[9] = delta_x[9] + nom_x[9]; + out_4640013062227700412[10] = delta_x[10] + nom_x[10]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_668705734016375974) { - out_668705734016375974[0] = -nom_x[0] + true_x[0]; - out_668705734016375974[1] = -nom_x[1] + true_x[1]; - out_668705734016375974[2] = -nom_x[2] + true_x[2]; - out_668705734016375974[3] = -nom_x[3] + true_x[3]; - out_668705734016375974[4] = -nom_x[4] + true_x[4]; - out_668705734016375974[5] = -nom_x[5] + true_x[5]; - out_668705734016375974[6] = -nom_x[6] + true_x[6]; - out_668705734016375974[7] = -nom_x[7] + true_x[7]; - out_668705734016375974[8] = -nom_x[8] + true_x[8]; - out_668705734016375974[9] = -nom_x[9] + true_x[9]; - out_668705734016375974[10] = -nom_x[10] + true_x[10]; +void inv_err_fun(double *nom_x, double *true_x, double *out_4915148707996812550) { + out_4915148707996812550[0] = -nom_x[0] + true_x[0]; + out_4915148707996812550[1] = -nom_x[1] + true_x[1]; + out_4915148707996812550[2] = -nom_x[2] + true_x[2]; + out_4915148707996812550[3] = -nom_x[3] + true_x[3]; + out_4915148707996812550[4] = -nom_x[4] + true_x[4]; + out_4915148707996812550[5] = -nom_x[5] + true_x[5]; + out_4915148707996812550[6] = -nom_x[6] + true_x[6]; + out_4915148707996812550[7] = -nom_x[7] + true_x[7]; + out_4915148707996812550[8] = -nom_x[8] + true_x[8]; + out_4915148707996812550[9] = -nom_x[9] + true_x[9]; + out_4915148707996812550[10] = -nom_x[10] + true_x[10]; } -void H_mod_fun(double *state, double *out_1646191520139698591) { - out_1646191520139698591[0] = 1.0; - out_1646191520139698591[1] = 0; - out_1646191520139698591[2] = 0; - out_1646191520139698591[3] = 0; - out_1646191520139698591[4] = 0; - out_1646191520139698591[5] = 0; - out_1646191520139698591[6] = 0; - out_1646191520139698591[7] = 0; - out_1646191520139698591[8] = 0; - out_1646191520139698591[9] = 0; - out_1646191520139698591[10] = 0; - out_1646191520139698591[11] = 0; - out_1646191520139698591[12] = 1.0; - out_1646191520139698591[13] = 0; - out_1646191520139698591[14] = 0; - out_1646191520139698591[15] = 0; - out_1646191520139698591[16] = 0; - out_1646191520139698591[17] = 0; - out_1646191520139698591[18] = 0; - out_1646191520139698591[19] = 0; - out_1646191520139698591[20] = 0; - out_1646191520139698591[21] = 0; - out_1646191520139698591[22] = 0; - out_1646191520139698591[23] = 0; - out_1646191520139698591[24] = 1.0; - out_1646191520139698591[25] = 0; - out_1646191520139698591[26] = 0; - out_1646191520139698591[27] = 0; - out_1646191520139698591[28] = 0; - out_1646191520139698591[29] = 0; - out_1646191520139698591[30] = 0; - out_1646191520139698591[31] = 0; - out_1646191520139698591[32] = 0; - out_1646191520139698591[33] = 0; - out_1646191520139698591[34] = 0; - out_1646191520139698591[35] = 0; - out_1646191520139698591[36] = 1.0; - out_1646191520139698591[37] = 0; - out_1646191520139698591[38] = 0; - out_1646191520139698591[39] = 0; - out_1646191520139698591[40] = 0; - out_1646191520139698591[41] = 0; - out_1646191520139698591[42] = 0; - out_1646191520139698591[43] = 0; - out_1646191520139698591[44] = 0; - out_1646191520139698591[45] = 0; - out_1646191520139698591[46] = 0; - out_1646191520139698591[47] = 0; - out_1646191520139698591[48] = 1.0; - out_1646191520139698591[49] = 0; - out_1646191520139698591[50] = 0; - out_1646191520139698591[51] = 0; - out_1646191520139698591[52] = 0; - out_1646191520139698591[53] = 0; - out_1646191520139698591[54] = 0; - out_1646191520139698591[55] = 0; - out_1646191520139698591[56] = 0; - out_1646191520139698591[57] = 0; - out_1646191520139698591[58] = 0; - out_1646191520139698591[59] = 0; - out_1646191520139698591[60] = 1.0; - out_1646191520139698591[61] = 0; - out_1646191520139698591[62] = 0; - out_1646191520139698591[63] = 0; - out_1646191520139698591[64] = 0; - out_1646191520139698591[65] = 0; - out_1646191520139698591[66] = 0; - out_1646191520139698591[67] = 0; - out_1646191520139698591[68] = 0; - out_1646191520139698591[69] = 0; - out_1646191520139698591[70] = 0; - out_1646191520139698591[71] = 0; - out_1646191520139698591[72] = 1.0; - out_1646191520139698591[73] = 0; - out_1646191520139698591[74] = 0; - out_1646191520139698591[75] = 0; - out_1646191520139698591[76] = 0; - out_1646191520139698591[77] = 0; - out_1646191520139698591[78] = 0; - out_1646191520139698591[79] = 0; - out_1646191520139698591[80] = 0; - out_1646191520139698591[81] = 0; - out_1646191520139698591[82] = 0; - out_1646191520139698591[83] = 0; - out_1646191520139698591[84] = 1.0; - out_1646191520139698591[85] = 0; - out_1646191520139698591[86] = 0; - out_1646191520139698591[87] = 0; - out_1646191520139698591[88] = 0; - out_1646191520139698591[89] = 0; - out_1646191520139698591[90] = 0; - out_1646191520139698591[91] = 0; - out_1646191520139698591[92] = 0; - out_1646191520139698591[93] = 0; - out_1646191520139698591[94] = 0; - out_1646191520139698591[95] = 0; - out_1646191520139698591[96] = 1.0; - out_1646191520139698591[97] = 0; - out_1646191520139698591[98] = 0; - out_1646191520139698591[99] = 0; - out_1646191520139698591[100] = 0; - out_1646191520139698591[101] = 0; - out_1646191520139698591[102] = 0; - out_1646191520139698591[103] = 0; - out_1646191520139698591[104] = 0; - out_1646191520139698591[105] = 0; - out_1646191520139698591[106] = 0; - out_1646191520139698591[107] = 0; - out_1646191520139698591[108] = 1.0; - out_1646191520139698591[109] = 0; - out_1646191520139698591[110] = 0; - out_1646191520139698591[111] = 0; - out_1646191520139698591[112] = 0; - out_1646191520139698591[113] = 0; - out_1646191520139698591[114] = 0; - out_1646191520139698591[115] = 0; - out_1646191520139698591[116] = 0; - out_1646191520139698591[117] = 0; - out_1646191520139698591[118] = 0; - out_1646191520139698591[119] = 0; - out_1646191520139698591[120] = 1.0; +void H_mod_fun(double *state, double *out_8574237875034322764) { + out_8574237875034322764[0] = 1.0; + out_8574237875034322764[1] = 0; + out_8574237875034322764[2] = 0; + out_8574237875034322764[3] = 0; + out_8574237875034322764[4] = 0; + out_8574237875034322764[5] = 0; + out_8574237875034322764[6] = 0; + out_8574237875034322764[7] = 0; + out_8574237875034322764[8] = 0; + out_8574237875034322764[9] = 0; + out_8574237875034322764[10] = 0; + out_8574237875034322764[11] = 0; + out_8574237875034322764[12] = 1.0; + out_8574237875034322764[13] = 0; + out_8574237875034322764[14] = 0; + out_8574237875034322764[15] = 0; + out_8574237875034322764[16] = 0; + out_8574237875034322764[17] = 0; + out_8574237875034322764[18] = 0; + out_8574237875034322764[19] = 0; + out_8574237875034322764[20] = 0; + out_8574237875034322764[21] = 0; + out_8574237875034322764[22] = 0; + out_8574237875034322764[23] = 0; + out_8574237875034322764[24] = 1.0; + out_8574237875034322764[25] = 0; + out_8574237875034322764[26] = 0; + out_8574237875034322764[27] = 0; + out_8574237875034322764[28] = 0; + out_8574237875034322764[29] = 0; + out_8574237875034322764[30] = 0; + out_8574237875034322764[31] = 0; + out_8574237875034322764[32] = 0; + out_8574237875034322764[33] = 0; + out_8574237875034322764[34] = 0; + out_8574237875034322764[35] = 0; + out_8574237875034322764[36] = 1.0; + out_8574237875034322764[37] = 0; + out_8574237875034322764[38] = 0; + out_8574237875034322764[39] = 0; + out_8574237875034322764[40] = 0; + out_8574237875034322764[41] = 0; + out_8574237875034322764[42] = 0; + out_8574237875034322764[43] = 0; + out_8574237875034322764[44] = 0; + out_8574237875034322764[45] = 0; + out_8574237875034322764[46] = 0; + out_8574237875034322764[47] = 0; + out_8574237875034322764[48] = 1.0; + out_8574237875034322764[49] = 0; + out_8574237875034322764[50] = 0; + out_8574237875034322764[51] = 0; + out_8574237875034322764[52] = 0; + out_8574237875034322764[53] = 0; + out_8574237875034322764[54] = 0; + out_8574237875034322764[55] = 0; + out_8574237875034322764[56] = 0; + out_8574237875034322764[57] = 0; + out_8574237875034322764[58] = 0; + out_8574237875034322764[59] = 0; + out_8574237875034322764[60] = 1.0; + out_8574237875034322764[61] = 0; + out_8574237875034322764[62] = 0; + out_8574237875034322764[63] = 0; + out_8574237875034322764[64] = 0; + out_8574237875034322764[65] = 0; + out_8574237875034322764[66] = 0; + out_8574237875034322764[67] = 0; + out_8574237875034322764[68] = 0; + out_8574237875034322764[69] = 0; + out_8574237875034322764[70] = 0; + out_8574237875034322764[71] = 0; + out_8574237875034322764[72] = 1.0; + out_8574237875034322764[73] = 0; + out_8574237875034322764[74] = 0; + out_8574237875034322764[75] = 0; + out_8574237875034322764[76] = 0; + out_8574237875034322764[77] = 0; + out_8574237875034322764[78] = 0; + out_8574237875034322764[79] = 0; + out_8574237875034322764[80] = 0; + out_8574237875034322764[81] = 0; + out_8574237875034322764[82] = 0; + out_8574237875034322764[83] = 0; + out_8574237875034322764[84] = 1.0; + out_8574237875034322764[85] = 0; + out_8574237875034322764[86] = 0; + out_8574237875034322764[87] = 0; + out_8574237875034322764[88] = 0; + out_8574237875034322764[89] = 0; + out_8574237875034322764[90] = 0; + out_8574237875034322764[91] = 0; + out_8574237875034322764[92] = 0; + out_8574237875034322764[93] = 0; + out_8574237875034322764[94] = 0; + out_8574237875034322764[95] = 0; + out_8574237875034322764[96] = 1.0; + out_8574237875034322764[97] = 0; + out_8574237875034322764[98] = 0; + out_8574237875034322764[99] = 0; + out_8574237875034322764[100] = 0; + out_8574237875034322764[101] = 0; + out_8574237875034322764[102] = 0; + out_8574237875034322764[103] = 0; + out_8574237875034322764[104] = 0; + out_8574237875034322764[105] = 0; + out_8574237875034322764[106] = 0; + out_8574237875034322764[107] = 0; + out_8574237875034322764[108] = 1.0; + out_8574237875034322764[109] = 0; + out_8574237875034322764[110] = 0; + out_8574237875034322764[111] = 0; + out_8574237875034322764[112] = 0; + out_8574237875034322764[113] = 0; + out_8574237875034322764[114] = 0; + out_8574237875034322764[115] = 0; + out_8574237875034322764[116] = 0; + out_8574237875034322764[117] = 0; + out_8574237875034322764[118] = 0; + out_8574237875034322764[119] = 0; + out_8574237875034322764[120] = 1.0; } -void f_fun(double *state, double dt, double *out_8136264243716214718) { - out_8136264243716214718[0] = dt*state[3] + state[0]; - out_8136264243716214718[1] = dt*state[4] + state[1]; - out_8136264243716214718[2] = dt*state[5] + state[2]; - out_8136264243716214718[3] = state[3]; - out_8136264243716214718[4] = state[4]; - out_8136264243716214718[5] = state[5]; - out_8136264243716214718[6] = dt*state[7] + state[6]; - out_8136264243716214718[7] = dt*state[8] + state[7]; - out_8136264243716214718[8] = state[8]; - out_8136264243716214718[9] = state[9]; - out_8136264243716214718[10] = state[10]; +void f_fun(double *state, double dt, double *out_5636831905979297775) { + out_5636831905979297775[0] = dt*state[3] + state[0]; + out_5636831905979297775[1] = dt*state[4] + state[1]; + out_5636831905979297775[2] = dt*state[5] + state[2]; + out_5636831905979297775[3] = state[3]; + out_5636831905979297775[4] = state[4]; + out_5636831905979297775[5] = state[5]; + out_5636831905979297775[6] = dt*state[7] + state[6]; + out_5636831905979297775[7] = dt*state[8] + state[7]; + out_5636831905979297775[8] = state[8]; + out_5636831905979297775[9] = state[9]; + out_5636831905979297775[10] = state[10]; } -void F_fun(double *state, double dt, double *out_4236213521667949352) { - out_4236213521667949352[0] = 1; - out_4236213521667949352[1] = 0; - out_4236213521667949352[2] = 0; - out_4236213521667949352[3] = dt; - out_4236213521667949352[4] = 0; - out_4236213521667949352[5] = 0; - out_4236213521667949352[6] = 0; - out_4236213521667949352[7] = 0; - out_4236213521667949352[8] = 0; - out_4236213521667949352[9] = 0; - out_4236213521667949352[10] = 0; - out_4236213521667949352[11] = 0; - out_4236213521667949352[12] = 1; - out_4236213521667949352[13] = 0; - out_4236213521667949352[14] = 0; - out_4236213521667949352[15] = dt; - out_4236213521667949352[16] = 0; - out_4236213521667949352[17] = 0; - out_4236213521667949352[18] = 0; - out_4236213521667949352[19] = 0; - out_4236213521667949352[20] = 0; - out_4236213521667949352[21] = 0; - out_4236213521667949352[22] = 0; - out_4236213521667949352[23] = 0; - out_4236213521667949352[24] = 1; - out_4236213521667949352[25] = 0; - out_4236213521667949352[26] = 0; - out_4236213521667949352[27] = dt; - out_4236213521667949352[28] = 0; - out_4236213521667949352[29] = 0; - out_4236213521667949352[30] = 0; - out_4236213521667949352[31] = 0; - out_4236213521667949352[32] = 0; - out_4236213521667949352[33] = 0; - out_4236213521667949352[34] = 0; - out_4236213521667949352[35] = 0; - out_4236213521667949352[36] = 1; - out_4236213521667949352[37] = 0; - out_4236213521667949352[38] = 0; - out_4236213521667949352[39] = 0; - out_4236213521667949352[40] = 0; - out_4236213521667949352[41] = 0; - out_4236213521667949352[42] = 0; - out_4236213521667949352[43] = 0; - out_4236213521667949352[44] = 0; - out_4236213521667949352[45] = 0; - out_4236213521667949352[46] = 0; - out_4236213521667949352[47] = 0; - out_4236213521667949352[48] = 1; - out_4236213521667949352[49] = 0; - out_4236213521667949352[50] = 0; - out_4236213521667949352[51] = 0; - out_4236213521667949352[52] = 0; - out_4236213521667949352[53] = 0; - out_4236213521667949352[54] = 0; - out_4236213521667949352[55] = 0; - out_4236213521667949352[56] = 0; - out_4236213521667949352[57] = 0; - out_4236213521667949352[58] = 0; - out_4236213521667949352[59] = 0; - out_4236213521667949352[60] = 1; - out_4236213521667949352[61] = 0; - out_4236213521667949352[62] = 0; - out_4236213521667949352[63] = 0; - out_4236213521667949352[64] = 0; - out_4236213521667949352[65] = 0; - out_4236213521667949352[66] = 0; - out_4236213521667949352[67] = 0; - out_4236213521667949352[68] = 0; - out_4236213521667949352[69] = 0; - out_4236213521667949352[70] = 0; - out_4236213521667949352[71] = 0; - out_4236213521667949352[72] = 1; - out_4236213521667949352[73] = dt; - out_4236213521667949352[74] = 0; - out_4236213521667949352[75] = 0; - out_4236213521667949352[76] = 0; - out_4236213521667949352[77] = 0; - out_4236213521667949352[78] = 0; - out_4236213521667949352[79] = 0; - out_4236213521667949352[80] = 0; - out_4236213521667949352[81] = 0; - out_4236213521667949352[82] = 0; - out_4236213521667949352[83] = 0; - out_4236213521667949352[84] = 1; - out_4236213521667949352[85] = dt; - out_4236213521667949352[86] = 0; - out_4236213521667949352[87] = 0; - out_4236213521667949352[88] = 0; - out_4236213521667949352[89] = 0; - out_4236213521667949352[90] = 0; - out_4236213521667949352[91] = 0; - out_4236213521667949352[92] = 0; - out_4236213521667949352[93] = 0; - out_4236213521667949352[94] = 0; - out_4236213521667949352[95] = 0; - out_4236213521667949352[96] = 1; - out_4236213521667949352[97] = 0; - out_4236213521667949352[98] = 0; - out_4236213521667949352[99] = 0; - out_4236213521667949352[100] = 0; - out_4236213521667949352[101] = 0; - out_4236213521667949352[102] = 0; - out_4236213521667949352[103] = 0; - out_4236213521667949352[104] = 0; - out_4236213521667949352[105] = 0; - out_4236213521667949352[106] = 0; - out_4236213521667949352[107] = 0; - out_4236213521667949352[108] = 1; - out_4236213521667949352[109] = 0; - out_4236213521667949352[110] = 0; - out_4236213521667949352[111] = 0; - out_4236213521667949352[112] = 0; - out_4236213521667949352[113] = 0; - out_4236213521667949352[114] = 0; - out_4236213521667949352[115] = 0; - out_4236213521667949352[116] = 0; - out_4236213521667949352[117] = 0; - out_4236213521667949352[118] = 0; - out_4236213521667949352[119] = 0; - out_4236213521667949352[120] = 1; +void F_fun(double *state, double dt, double *out_2727942986966876467) { + out_2727942986966876467[0] = 1; + out_2727942986966876467[1] = 0; + out_2727942986966876467[2] = 0; + out_2727942986966876467[3] = dt; + out_2727942986966876467[4] = 0; + out_2727942986966876467[5] = 0; + out_2727942986966876467[6] = 0; + out_2727942986966876467[7] = 0; + out_2727942986966876467[8] = 0; + out_2727942986966876467[9] = 0; + out_2727942986966876467[10] = 0; + out_2727942986966876467[11] = 0; + out_2727942986966876467[12] = 1; + out_2727942986966876467[13] = 0; + out_2727942986966876467[14] = 0; + out_2727942986966876467[15] = dt; + out_2727942986966876467[16] = 0; + out_2727942986966876467[17] = 0; + out_2727942986966876467[18] = 0; + out_2727942986966876467[19] = 0; + out_2727942986966876467[20] = 0; + out_2727942986966876467[21] = 0; + out_2727942986966876467[22] = 0; + out_2727942986966876467[23] = 0; + out_2727942986966876467[24] = 1; + out_2727942986966876467[25] = 0; + out_2727942986966876467[26] = 0; + out_2727942986966876467[27] = dt; + out_2727942986966876467[28] = 0; + out_2727942986966876467[29] = 0; + out_2727942986966876467[30] = 0; + out_2727942986966876467[31] = 0; + out_2727942986966876467[32] = 0; + out_2727942986966876467[33] = 0; + out_2727942986966876467[34] = 0; + out_2727942986966876467[35] = 0; + out_2727942986966876467[36] = 1; + out_2727942986966876467[37] = 0; + out_2727942986966876467[38] = 0; + out_2727942986966876467[39] = 0; + out_2727942986966876467[40] = 0; + out_2727942986966876467[41] = 0; + out_2727942986966876467[42] = 0; + out_2727942986966876467[43] = 0; + out_2727942986966876467[44] = 0; + out_2727942986966876467[45] = 0; + out_2727942986966876467[46] = 0; + out_2727942986966876467[47] = 0; + out_2727942986966876467[48] = 1; + out_2727942986966876467[49] = 0; + out_2727942986966876467[50] = 0; + out_2727942986966876467[51] = 0; + out_2727942986966876467[52] = 0; + out_2727942986966876467[53] = 0; + out_2727942986966876467[54] = 0; + out_2727942986966876467[55] = 0; + out_2727942986966876467[56] = 0; + out_2727942986966876467[57] = 0; + out_2727942986966876467[58] = 0; + out_2727942986966876467[59] = 0; + out_2727942986966876467[60] = 1; + out_2727942986966876467[61] = 0; + out_2727942986966876467[62] = 0; + out_2727942986966876467[63] = 0; + out_2727942986966876467[64] = 0; + out_2727942986966876467[65] = 0; + out_2727942986966876467[66] = 0; + out_2727942986966876467[67] = 0; + out_2727942986966876467[68] = 0; + out_2727942986966876467[69] = 0; + out_2727942986966876467[70] = 0; + out_2727942986966876467[71] = 0; + out_2727942986966876467[72] = 1; + out_2727942986966876467[73] = dt; + out_2727942986966876467[74] = 0; + out_2727942986966876467[75] = 0; + out_2727942986966876467[76] = 0; + out_2727942986966876467[77] = 0; + out_2727942986966876467[78] = 0; + out_2727942986966876467[79] = 0; + out_2727942986966876467[80] = 0; + out_2727942986966876467[81] = 0; + out_2727942986966876467[82] = 0; + out_2727942986966876467[83] = 0; + out_2727942986966876467[84] = 1; + out_2727942986966876467[85] = dt; + out_2727942986966876467[86] = 0; + out_2727942986966876467[87] = 0; + out_2727942986966876467[88] = 0; + out_2727942986966876467[89] = 0; + out_2727942986966876467[90] = 0; + out_2727942986966876467[91] = 0; + out_2727942986966876467[92] = 0; + out_2727942986966876467[93] = 0; + out_2727942986966876467[94] = 0; + out_2727942986966876467[95] = 0; + out_2727942986966876467[96] = 1; + out_2727942986966876467[97] = 0; + out_2727942986966876467[98] = 0; + out_2727942986966876467[99] = 0; + out_2727942986966876467[100] = 0; + out_2727942986966876467[101] = 0; + out_2727942986966876467[102] = 0; + out_2727942986966876467[103] = 0; + out_2727942986966876467[104] = 0; + out_2727942986966876467[105] = 0; + out_2727942986966876467[106] = 0; + out_2727942986966876467[107] = 0; + out_2727942986966876467[108] = 1; + out_2727942986966876467[109] = 0; + out_2727942986966876467[110] = 0; + out_2727942986966876467[111] = 0; + out_2727942986966876467[112] = 0; + out_2727942986966876467[113] = 0; + out_2727942986966876467[114] = 0; + out_2727942986966876467[115] = 0; + out_2727942986966876467[116] = 0; + out_2727942986966876467[117] = 0; + out_2727942986966876467[118] = 0; + out_2727942986966876467[119] = 0; + out_2727942986966876467[120] = 1; } -void h_6(double *state, double *sat_pos, double *out_8352111296884602789) { - out_8352111296884602789[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + state[6]; +void h_6(double *state, double *sat_pos, double *out_4554215930920042575) { + out_4554215930920042575[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + state[6]; } -void H_6(double *state, double *sat_pos, double *out_2202359500111385714) { - out_2202359500111385714[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2202359500111385714[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2202359500111385714[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2202359500111385714[3] = 0; - out_2202359500111385714[4] = 0; - out_2202359500111385714[5] = 0; - out_2202359500111385714[6] = 1; - out_2202359500111385714[7] = 0; - out_2202359500111385714[8] = 0; - out_2202359500111385714[9] = 0; - out_2202359500111385714[10] = 0; +void H_6(double *state, double *sat_pos, double *out_895428558576169950) { + out_895428558576169950[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_895428558576169950[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_895428558576169950[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_895428558576169950[3] = 0; + out_895428558576169950[4] = 0; + out_895428558576169950[5] = 0; + out_895428558576169950[6] = 1; + out_895428558576169950[7] = 0; + out_895428558576169950[8] = 0; + out_895428558576169950[9] = 0; + out_895428558576169950[10] = 0; } -void h_20(double *state, double *sat_pos, double *out_4887672178428492502) { - out_4887672178428492502[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + sat_pos[3]*state[10] + state[6] + state[9]; +void h_20(double *state, double *sat_pos, double *out_6704926246356191984) { + out_6704926246356191984[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + sat_pos[3]*state[10] + state[6] + state[9]; } -void H_20(double *state, double *sat_pos, double *out_4961949425089895635) { - out_4961949425089895635[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_4961949425089895635[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_4961949425089895635[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_4961949425089895635[3] = 0; - out_4961949425089895635[4] = 0; - out_4961949425089895635[5] = 0; - out_4961949425089895635[6] = 1; - out_4961949425089895635[7] = 0; - out_4961949425089895635[8] = 0; - out_4961949425089895635[9] = 1; - out_4961949425089895635[10] = sat_pos[3]; +void H_20(double *state, double *sat_pos, double *out_3575717658219428128) { + out_3575717658219428128[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_3575717658219428128[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_3575717658219428128[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_3575717658219428128[3] = 0; + out_3575717658219428128[4] = 0; + out_3575717658219428128[5] = 0; + out_3575717658219428128[6] = 1; + out_3575717658219428128[7] = 0; + out_3575717658219428128[8] = 0; + out_3575717658219428128[9] = 1; + out_3575717658219428128[10] = sat_pos[3]; } -void h_7(double *state, double *sat_pos_vel, double *out_191603051630805475) { - out_191603051630805475[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; +void h_7(double *state, double *sat_pos_vel, double *out_6430340606903371855) { + out_6430340606903371855[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; } -void H_7(double *state, double *sat_pos_vel, double *out_7197851591855342328) { - out_7197851591855342328[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[6] = 0; - out_7197851591855342328[7] = 1; - out_7197851591855342328[8] = 0; - out_7197851591855342328[9] = 0; - out_7197851591855342328[10] = 0; +void H_7(double *state, double *sat_pos_vel, double *out_4789129994195662485) { + out_4789129994195662485[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[6] = 0; + out_4789129994195662485[7] = 1; + out_4789129994195662485[8] = 0; + out_4789129994195662485[9] = 0; + out_4789129994195662485[10] = 0; } -void h_21(double *state, double *sat_pos_vel, double *out_191603051630805475) { - out_191603051630805475[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; +void h_21(double *state, double *sat_pos_vel, double *out_6430340606903371855) { + out_6430340606903371855[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; } -void H_21(double *state, double *sat_pos_vel, double *out_7197851591855342328) { - out_7197851591855342328[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_7197851591855342328[6] = 0; - out_7197851591855342328[7] = 1; - out_7197851591855342328[8] = 0; - out_7197851591855342328[9] = 0; - out_7197851591855342328[10] = 0; +void H_21(double *state, double *sat_pos_vel, double *out_4789129994195662485) { + out_4789129994195662485[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_4789129994195662485[6] = 0; + out_4789129994195662485[7] = 1; + out_4789129994195662485[8] = 0; + out_4789129994195662485[9] = 0; + out_4789129994195662485[10] = 0; } #include #include @@ -506,44 +506,44 @@ void gnss_update_7(double *in_x, double *in_P, double *in_z, double *in_R, doubl void gnss_update_21(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<1, 3, 0>(in_x, in_P, h_21, H_21, NULL, in_z, in_R, in_ea, MAHA_THRESH_21); } -void gnss_err_fun(double *nom_x, double *delta_x, double *out_3985733553669045281) { - err_fun(nom_x, delta_x, out_3985733553669045281); +void gnss_err_fun(double *nom_x, double *delta_x, double *out_4640013062227700412) { + err_fun(nom_x, delta_x, out_4640013062227700412); } -void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_668705734016375974) { - inv_err_fun(nom_x, true_x, out_668705734016375974); +void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_4915148707996812550) { + inv_err_fun(nom_x, true_x, out_4915148707996812550); } -void gnss_H_mod_fun(double *state, double *out_1646191520139698591) { - H_mod_fun(state, out_1646191520139698591); +void gnss_H_mod_fun(double *state, double *out_8574237875034322764) { + H_mod_fun(state, out_8574237875034322764); } -void gnss_f_fun(double *state, double dt, double *out_8136264243716214718) { - f_fun(state, dt, out_8136264243716214718); +void gnss_f_fun(double *state, double dt, double *out_5636831905979297775) { + f_fun(state, dt, out_5636831905979297775); } -void gnss_F_fun(double *state, double dt, double *out_4236213521667949352) { - F_fun(state, dt, out_4236213521667949352); +void gnss_F_fun(double *state, double dt, double *out_2727942986966876467) { + F_fun(state, dt, out_2727942986966876467); } -void gnss_h_6(double *state, double *sat_pos, double *out_8352111296884602789) { - h_6(state, sat_pos, out_8352111296884602789); +void gnss_h_6(double *state, double *sat_pos, double *out_4554215930920042575) { + h_6(state, sat_pos, out_4554215930920042575); } -void gnss_H_6(double *state, double *sat_pos, double *out_2202359500111385714) { - H_6(state, sat_pos, out_2202359500111385714); +void gnss_H_6(double *state, double *sat_pos, double *out_895428558576169950) { + H_6(state, sat_pos, out_895428558576169950); } -void gnss_h_20(double *state, double *sat_pos, double *out_4887672178428492502) { - h_20(state, sat_pos, out_4887672178428492502); +void gnss_h_20(double *state, double *sat_pos, double *out_6704926246356191984) { + h_20(state, sat_pos, out_6704926246356191984); } -void gnss_H_20(double *state, double *sat_pos, double *out_4961949425089895635) { - H_20(state, sat_pos, out_4961949425089895635); +void gnss_H_20(double *state, double *sat_pos, double *out_3575717658219428128) { + H_20(state, sat_pos, out_3575717658219428128); } -void gnss_h_7(double *state, double *sat_pos_vel, double *out_191603051630805475) { - h_7(state, sat_pos_vel, out_191603051630805475); +void gnss_h_7(double *state, double *sat_pos_vel, double *out_6430340606903371855) { + h_7(state, sat_pos_vel, out_6430340606903371855); } -void gnss_H_7(double *state, double *sat_pos_vel, double *out_7197851591855342328) { - H_7(state, sat_pos_vel, out_7197851591855342328); +void gnss_H_7(double *state, double *sat_pos_vel, double *out_4789129994195662485) { + H_7(state, sat_pos_vel, out_4789129994195662485); } -void gnss_h_21(double *state, double *sat_pos_vel, double *out_191603051630805475) { - h_21(state, sat_pos_vel, out_191603051630805475); +void gnss_h_21(double *state, double *sat_pos_vel, double *out_6430340606903371855) { + h_21(state, sat_pos_vel, out_6430340606903371855); } -void gnss_H_21(double *state, double *sat_pos_vel, double *out_7197851591855342328) { - H_21(state, sat_pos_vel, out_7197851591855342328); +void gnss_H_21(double *state, double *sat_pos_vel, double *out_4789129994195662485) { + H_21(state, sat_pos_vel, out_4789129994195662485); } void gnss_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/gnss.h b/selfdrive/locationd/models/generated/gnss.h index a37abe221..fde56c35a 100644 --- a/selfdrive/locationd/models/generated/gnss.h +++ b/selfdrive/locationd/models/generated/gnss.h @@ -5,18 +5,18 @@ void gnss_update_6(double *in_x, double *in_P, double *in_z, double *in_R, doubl void gnss_update_20(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void gnss_update_7(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void gnss_update_21(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void gnss_err_fun(double *nom_x, double *delta_x, double *out_3985733553669045281); -void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_668705734016375974); -void gnss_H_mod_fun(double *state, double *out_1646191520139698591); -void gnss_f_fun(double *state, double dt, double *out_8136264243716214718); -void gnss_F_fun(double *state, double dt, double *out_4236213521667949352); -void gnss_h_6(double *state, double *sat_pos, double *out_8352111296884602789); -void gnss_H_6(double *state, double *sat_pos, double *out_2202359500111385714); -void gnss_h_20(double *state, double *sat_pos, double *out_4887672178428492502); -void gnss_H_20(double *state, double *sat_pos, double *out_4961949425089895635); -void gnss_h_7(double *state, double *sat_pos_vel, double *out_191603051630805475); -void gnss_H_7(double *state, double *sat_pos_vel, double *out_7197851591855342328); -void gnss_h_21(double *state, double *sat_pos_vel, double *out_191603051630805475); -void gnss_H_21(double *state, double *sat_pos_vel, double *out_7197851591855342328); +void gnss_err_fun(double *nom_x, double *delta_x, double *out_4640013062227700412); +void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_4915148707996812550); +void gnss_H_mod_fun(double *state, double *out_8574237875034322764); +void gnss_f_fun(double *state, double dt, double *out_5636831905979297775); +void gnss_F_fun(double *state, double dt, double *out_2727942986966876467); +void gnss_h_6(double *state, double *sat_pos, double *out_4554215930920042575); +void gnss_H_6(double *state, double *sat_pos, double *out_895428558576169950); +void gnss_h_20(double *state, double *sat_pos, double *out_6704926246356191984); +void gnss_H_20(double *state, double *sat_pos, double *out_3575717658219428128); +void gnss_h_7(double *state, double *sat_pos_vel, double *out_6430340606903371855); +void gnss_H_7(double *state, double *sat_pos_vel, double *out_4789129994195662485); +void gnss_h_21(double *state, double *sat_pos_vel, double *out_6430340606903371855); +void gnss_H_21(double *state, double *sat_pos_vel, double *out_4789129994195662485); void gnss_predict(double *in_x, double *in_P, double *in_Q, double dt); } \ No newline at end of file diff --git a/selfdrive/locationd/models/generated/libkf.so b/selfdrive/locationd/models/generated/libkf.so index 7e2a69863..da587f8b2 100755 Binary files a/selfdrive/locationd/models/generated/libkf.so and b/selfdrive/locationd/models/generated/libkf.so differ diff --git a/selfdrive/locationd/models/generated/live.cpp b/selfdrive/locationd/models/generated/live.cpp index a8905b4d6..84d0e0f26 100644 --- a/selfdrive/locationd/models/generated/live.cpp +++ b/selfdrive/locationd/models/generated/live.cpp @@ -22,1683 +22,1683 @@ const static double MAHA_THRESH_33 = 7.814727903251177; * * * This file is part of 'ekf' * ******************************************************************************/ -void H(double *in_vec, double *out_4368495907718343571) { - out_4368495907718343571[0] = 0; - out_4368495907718343571[1] = -sin(in_vec[1])*sin(in_vec[2])*in_vec[4] - sin(in_vec[1])*cos(in_vec[2])*in_vec[3] - cos(in_vec[1])*in_vec[5]; - out_4368495907718343571[2] = -sin(in_vec[2])*cos(in_vec[1])*in_vec[3] + cos(in_vec[1])*cos(in_vec[2])*in_vec[4]; - out_4368495907718343571[3] = cos(in_vec[1])*cos(in_vec[2]); - out_4368495907718343571[4] = sin(in_vec[2])*cos(in_vec[1]); - out_4368495907718343571[5] = -sin(in_vec[1]); - out_4368495907718343571[6] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (-sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*in_vec[5]; - out_4368495907718343571[7] = -sin(in_vec[0])*sin(in_vec[1])*in_vec[5] + sin(in_vec[0])*sin(in_vec[2])*cos(in_vec[1])*in_vec[4] + sin(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; - out_4368495907718343571[8] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]))*in_vec[4]; - out_4368495907718343571[9] = sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]); - out_4368495907718343571[10] = sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) + cos(in_vec[0])*cos(in_vec[2]); - out_4368495907718343571[11] = sin(in_vec[0])*cos(in_vec[1]); - out_4368495907718343571[12] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (-sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) + sin(in_vec[2])*cos(in_vec[0]))*in_vec[3] - sin(in_vec[0])*cos(in_vec[1])*in_vec[5]; - out_4368495907718343571[13] = -sin(in_vec[1])*cos(in_vec[0])*in_vec[5] + sin(in_vec[2])*cos(in_vec[0])*cos(in_vec[1])*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; - out_4368495907718343571[14] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (sin(in_vec[0])*cos(in_vec[2]) - sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[3]; - out_4368495907718343571[15] = sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]); - out_4368495907718343571[16] = -sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]); - out_4368495907718343571[17] = cos(in_vec[0])*cos(in_vec[1]); +void H(double *in_vec, double *out_6240008686817713408) { + out_6240008686817713408[0] = 0; + out_6240008686817713408[1] = -sin(in_vec[1])*sin(in_vec[2])*in_vec[4] - sin(in_vec[1])*cos(in_vec[2])*in_vec[3] - cos(in_vec[1])*in_vec[5]; + out_6240008686817713408[2] = -sin(in_vec[2])*cos(in_vec[1])*in_vec[3] + cos(in_vec[1])*cos(in_vec[2])*in_vec[4]; + out_6240008686817713408[3] = cos(in_vec[1])*cos(in_vec[2]); + out_6240008686817713408[4] = sin(in_vec[2])*cos(in_vec[1]); + out_6240008686817713408[5] = -sin(in_vec[1]); + out_6240008686817713408[6] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (-sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_6240008686817713408[7] = -sin(in_vec[0])*sin(in_vec[1])*in_vec[5] + sin(in_vec[0])*sin(in_vec[2])*cos(in_vec[1])*in_vec[4] + sin(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_6240008686817713408[8] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]))*in_vec[4]; + out_6240008686817713408[9] = sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]); + out_6240008686817713408[10] = sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) + cos(in_vec[0])*cos(in_vec[2]); + out_6240008686817713408[11] = sin(in_vec[0])*cos(in_vec[1]); + out_6240008686817713408[12] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (-sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) + sin(in_vec[2])*cos(in_vec[0]))*in_vec[3] - sin(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_6240008686817713408[13] = -sin(in_vec[1])*cos(in_vec[0])*in_vec[5] + sin(in_vec[2])*cos(in_vec[0])*cos(in_vec[1])*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_6240008686817713408[14] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (sin(in_vec[0])*cos(in_vec[2]) - sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[3]; + out_6240008686817713408[15] = sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]); + out_6240008686817713408[16] = -sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]); + out_6240008686817713408[17] = cos(in_vec[0])*cos(in_vec[1]); } -void err_fun(double *nom_x, double *delta_x, double *out_4465536791498929799) { - out_4465536791498929799[0] = delta_x[0] + nom_x[0]; - out_4465536791498929799[1] = delta_x[1] + nom_x[1]; - out_4465536791498929799[2] = delta_x[2] + nom_x[2]; - out_4465536791498929799[3] = -0.5*delta_x[3]*nom_x[4] - 0.5*delta_x[4]*nom_x[5] - 0.5*delta_x[5]*nom_x[6] + 1.0*nom_x[3]; - out_4465536791498929799[4] = 0.5*delta_x[3]*nom_x[3] + 0.5*delta_x[4]*nom_x[6] - 0.5*delta_x[5]*nom_x[5] + 1.0*nom_x[4]; - out_4465536791498929799[5] = -0.5*delta_x[3]*nom_x[6] + 0.5*delta_x[4]*nom_x[3] + 0.5*delta_x[5]*nom_x[4] + 1.0*nom_x[5]; - out_4465536791498929799[6] = 0.5*delta_x[3]*nom_x[5] - 0.5*delta_x[4]*nom_x[4] + 0.5*delta_x[5]*nom_x[3] + 1.0*nom_x[6]; - out_4465536791498929799[7] = delta_x[6] + nom_x[7]; - out_4465536791498929799[8] = delta_x[7] + nom_x[8]; - out_4465536791498929799[9] = delta_x[8] + nom_x[9]; - out_4465536791498929799[10] = delta_x[9] + nom_x[10]; - out_4465536791498929799[11] = delta_x[10] + nom_x[11]; - out_4465536791498929799[12] = delta_x[11] + nom_x[12]; - out_4465536791498929799[13] = delta_x[12] + nom_x[13]; - out_4465536791498929799[14] = delta_x[13] + nom_x[14]; - out_4465536791498929799[15] = delta_x[14] + nom_x[15]; - out_4465536791498929799[16] = delta_x[15] + nom_x[16]; - out_4465536791498929799[17] = delta_x[16] + nom_x[17]; - out_4465536791498929799[18] = delta_x[17] + nom_x[18]; - out_4465536791498929799[19] = delta_x[18] + nom_x[19]; - out_4465536791498929799[20] = delta_x[19] + nom_x[20]; - out_4465536791498929799[21] = delta_x[20] + nom_x[21]; +void err_fun(double *nom_x, double *delta_x, double *out_3690665086918622964) { + out_3690665086918622964[0] = delta_x[0] + nom_x[0]; + out_3690665086918622964[1] = delta_x[1] + nom_x[1]; + out_3690665086918622964[2] = delta_x[2] + nom_x[2]; + out_3690665086918622964[3] = -0.5*delta_x[3]*nom_x[4] - 0.5*delta_x[4]*nom_x[5] - 0.5*delta_x[5]*nom_x[6] + 1.0*nom_x[3]; + out_3690665086918622964[4] = 0.5*delta_x[3]*nom_x[3] + 0.5*delta_x[4]*nom_x[6] - 0.5*delta_x[5]*nom_x[5] + 1.0*nom_x[4]; + out_3690665086918622964[5] = -0.5*delta_x[3]*nom_x[6] + 0.5*delta_x[4]*nom_x[3] + 0.5*delta_x[5]*nom_x[4] + 1.0*nom_x[5]; + out_3690665086918622964[6] = 0.5*delta_x[3]*nom_x[5] - 0.5*delta_x[4]*nom_x[4] + 0.5*delta_x[5]*nom_x[3] + 1.0*nom_x[6]; + out_3690665086918622964[7] = delta_x[6] + nom_x[7]; + out_3690665086918622964[8] = delta_x[7] + nom_x[8]; + out_3690665086918622964[9] = delta_x[8] + nom_x[9]; + out_3690665086918622964[10] = delta_x[9] + nom_x[10]; + out_3690665086918622964[11] = delta_x[10] + nom_x[11]; + out_3690665086918622964[12] = delta_x[11] + nom_x[12]; + out_3690665086918622964[13] = delta_x[12] + nom_x[13]; + out_3690665086918622964[14] = delta_x[13] + nom_x[14]; + out_3690665086918622964[15] = delta_x[14] + nom_x[15]; + out_3690665086918622964[16] = delta_x[15] + nom_x[16]; + out_3690665086918622964[17] = delta_x[16] + nom_x[17]; + out_3690665086918622964[18] = delta_x[17] + nom_x[18]; + out_3690665086918622964[19] = delta_x[18] + nom_x[19]; + out_3690665086918622964[20] = delta_x[19] + nom_x[20]; + out_3690665086918622964[21] = delta_x[20] + nom_x[21]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_4242153094211941637) { - out_4242153094211941637[0] = -nom_x[0] + true_x[0]; - out_4242153094211941637[1] = -nom_x[1] + true_x[1]; - out_4242153094211941637[2] = -nom_x[2] + true_x[2]; - out_4242153094211941637[3] = 2*nom_x[3]*true_x[4] - 2*nom_x[4]*true_x[3] + 2*nom_x[5]*true_x[6] - 2*nom_x[6]*true_x[5]; - out_4242153094211941637[4] = 2*nom_x[3]*true_x[5] - 2*nom_x[4]*true_x[6] - 2*nom_x[5]*true_x[3] + 2*nom_x[6]*true_x[4]; - out_4242153094211941637[5] = 2*nom_x[3]*true_x[6] + 2*nom_x[4]*true_x[5] - 2*nom_x[5]*true_x[4] - 2*nom_x[6]*true_x[3]; - out_4242153094211941637[6] = -nom_x[7] + true_x[7]; - out_4242153094211941637[7] = -nom_x[8] + true_x[8]; - out_4242153094211941637[8] = -nom_x[9] + true_x[9]; - out_4242153094211941637[9] = -nom_x[10] + true_x[10]; - out_4242153094211941637[10] = -nom_x[11] + true_x[11]; - out_4242153094211941637[11] = -nom_x[12] + true_x[12]; - out_4242153094211941637[12] = -nom_x[13] + true_x[13]; - out_4242153094211941637[13] = -nom_x[14] + true_x[14]; - out_4242153094211941637[14] = -nom_x[15] + true_x[15]; - out_4242153094211941637[15] = -nom_x[16] + true_x[16]; - out_4242153094211941637[16] = -nom_x[17] + true_x[17]; - out_4242153094211941637[17] = -nom_x[18] + true_x[18]; - out_4242153094211941637[18] = -nom_x[19] + true_x[19]; - out_4242153094211941637[19] = -nom_x[20] + true_x[20]; - out_4242153094211941637[20] = -nom_x[21] + true_x[21]; +void inv_err_fun(double *nom_x, double *true_x, double *out_8615868703535681088) { + out_8615868703535681088[0] = -nom_x[0] + true_x[0]; + out_8615868703535681088[1] = -nom_x[1] + true_x[1]; + out_8615868703535681088[2] = -nom_x[2] + true_x[2]; + out_8615868703535681088[3] = 2*nom_x[3]*true_x[4] - 2*nom_x[4]*true_x[3] + 2*nom_x[5]*true_x[6] - 2*nom_x[6]*true_x[5]; + out_8615868703535681088[4] = 2*nom_x[3]*true_x[5] - 2*nom_x[4]*true_x[6] - 2*nom_x[5]*true_x[3] + 2*nom_x[6]*true_x[4]; + out_8615868703535681088[5] = 2*nom_x[3]*true_x[6] + 2*nom_x[4]*true_x[5] - 2*nom_x[5]*true_x[4] - 2*nom_x[6]*true_x[3]; + out_8615868703535681088[6] = -nom_x[7] + true_x[7]; + out_8615868703535681088[7] = -nom_x[8] + true_x[8]; + out_8615868703535681088[8] = -nom_x[9] + true_x[9]; + out_8615868703535681088[9] = -nom_x[10] + true_x[10]; + out_8615868703535681088[10] = -nom_x[11] + true_x[11]; + out_8615868703535681088[11] = -nom_x[12] + true_x[12]; + out_8615868703535681088[12] = -nom_x[13] + true_x[13]; + out_8615868703535681088[13] = -nom_x[14] + true_x[14]; + out_8615868703535681088[14] = -nom_x[15] + true_x[15]; + out_8615868703535681088[15] = -nom_x[16] + true_x[16]; + out_8615868703535681088[16] = -nom_x[17] + true_x[17]; + out_8615868703535681088[17] = -nom_x[18] + true_x[18]; + out_8615868703535681088[18] = -nom_x[19] + true_x[19]; + out_8615868703535681088[19] = -nom_x[20] + true_x[20]; + out_8615868703535681088[20] = -nom_x[21] + true_x[21]; } -void H_mod_fun(double *state, double *out_8694534732588551911) { - out_8694534732588551911[0] = 1.0; - out_8694534732588551911[1] = 0; - out_8694534732588551911[2] = 0; - out_8694534732588551911[3] = 0; - out_8694534732588551911[4] = 0; - out_8694534732588551911[5] = 0; - out_8694534732588551911[6] = 0; - out_8694534732588551911[7] = 0; - out_8694534732588551911[8] = 0; - out_8694534732588551911[9] = 0; - out_8694534732588551911[10] = 0; - out_8694534732588551911[11] = 0; - out_8694534732588551911[12] = 0; - out_8694534732588551911[13] = 0; - out_8694534732588551911[14] = 0; - out_8694534732588551911[15] = 0; - out_8694534732588551911[16] = 0; - out_8694534732588551911[17] = 0; - out_8694534732588551911[18] = 0; - out_8694534732588551911[19] = 0; - out_8694534732588551911[20] = 0; - out_8694534732588551911[21] = 0; - out_8694534732588551911[22] = 1.0; - out_8694534732588551911[23] = 0; - out_8694534732588551911[24] = 0; - out_8694534732588551911[25] = 0; - out_8694534732588551911[26] = 0; - out_8694534732588551911[27] = 0; - out_8694534732588551911[28] = 0; - out_8694534732588551911[29] = 0; - out_8694534732588551911[30] = 0; - out_8694534732588551911[31] = 0; - out_8694534732588551911[32] = 0; - out_8694534732588551911[33] = 0; - out_8694534732588551911[34] = 0; - out_8694534732588551911[35] = 0; - out_8694534732588551911[36] = 0; - out_8694534732588551911[37] = 0; - out_8694534732588551911[38] = 0; - out_8694534732588551911[39] = 0; - out_8694534732588551911[40] = 0; - out_8694534732588551911[41] = 0; - out_8694534732588551911[42] = 0; - out_8694534732588551911[43] = 0; - out_8694534732588551911[44] = 1.0; - out_8694534732588551911[45] = 0; - out_8694534732588551911[46] = 0; - out_8694534732588551911[47] = 0; - out_8694534732588551911[48] = 0; - out_8694534732588551911[49] = 0; - out_8694534732588551911[50] = 0; - out_8694534732588551911[51] = 0; - out_8694534732588551911[52] = 0; - out_8694534732588551911[53] = 0; - out_8694534732588551911[54] = 0; - out_8694534732588551911[55] = 0; - out_8694534732588551911[56] = 0; - out_8694534732588551911[57] = 0; - out_8694534732588551911[58] = 0; - out_8694534732588551911[59] = 0; - out_8694534732588551911[60] = 0; - out_8694534732588551911[61] = 0; - out_8694534732588551911[62] = 0; - out_8694534732588551911[63] = 0; - out_8694534732588551911[64] = 0; - out_8694534732588551911[65] = 0; - out_8694534732588551911[66] = -0.5*state[4]; - out_8694534732588551911[67] = -0.5*state[5]; - out_8694534732588551911[68] = -0.5*state[6]; - out_8694534732588551911[69] = 0; - out_8694534732588551911[70] = 0; - out_8694534732588551911[71] = 0; - out_8694534732588551911[72] = 0; - out_8694534732588551911[73] = 0; - out_8694534732588551911[74] = 0; - out_8694534732588551911[75] = 0; - out_8694534732588551911[76] = 0; - out_8694534732588551911[77] = 0; - out_8694534732588551911[78] = 0; - out_8694534732588551911[79] = 0; - out_8694534732588551911[80] = 0; - out_8694534732588551911[81] = 0; - out_8694534732588551911[82] = 0; - out_8694534732588551911[83] = 0; - out_8694534732588551911[84] = 0; - out_8694534732588551911[85] = 0; - out_8694534732588551911[86] = 0; - out_8694534732588551911[87] = 0.5*state[3]; - out_8694534732588551911[88] = 0.5*state[6]; - out_8694534732588551911[89] = -0.5*state[5]; - out_8694534732588551911[90] = 0; - out_8694534732588551911[91] = 0; - out_8694534732588551911[92] = 0; - out_8694534732588551911[93] = 0; - out_8694534732588551911[94] = 0; - out_8694534732588551911[95] = 0; - out_8694534732588551911[96] = 0; - out_8694534732588551911[97] = 0; - out_8694534732588551911[98] = 0; - out_8694534732588551911[99] = 0; - out_8694534732588551911[100] = 0; - out_8694534732588551911[101] = 0; - out_8694534732588551911[102] = 0; - out_8694534732588551911[103] = 0; - out_8694534732588551911[104] = 0; - out_8694534732588551911[105] = 0; - out_8694534732588551911[106] = 0; - out_8694534732588551911[107] = 0; - out_8694534732588551911[108] = -0.5*state[6]; - out_8694534732588551911[109] = 0.5*state[3]; - out_8694534732588551911[110] = 0.5*state[4]; - out_8694534732588551911[111] = 0; - out_8694534732588551911[112] = 0; - out_8694534732588551911[113] = 0; - out_8694534732588551911[114] = 0; - out_8694534732588551911[115] = 0; - out_8694534732588551911[116] = 0; - out_8694534732588551911[117] = 0; - out_8694534732588551911[118] = 0; - out_8694534732588551911[119] = 0; - out_8694534732588551911[120] = 0; - out_8694534732588551911[121] = 0; - out_8694534732588551911[122] = 0; - out_8694534732588551911[123] = 0; - out_8694534732588551911[124] = 0; - out_8694534732588551911[125] = 0; - out_8694534732588551911[126] = 0; - out_8694534732588551911[127] = 0; - out_8694534732588551911[128] = 0; - out_8694534732588551911[129] = 0.5*state[5]; - out_8694534732588551911[130] = -0.5*state[4]; - out_8694534732588551911[131] = 0.5*state[3]; - out_8694534732588551911[132] = 0; - out_8694534732588551911[133] = 0; - out_8694534732588551911[134] = 0; - out_8694534732588551911[135] = 0; - out_8694534732588551911[136] = 0; - out_8694534732588551911[137] = 0; - out_8694534732588551911[138] = 0; - out_8694534732588551911[139] = 0; - out_8694534732588551911[140] = 0; - out_8694534732588551911[141] = 0; - out_8694534732588551911[142] = 0; - out_8694534732588551911[143] = 0; - out_8694534732588551911[144] = 0; - out_8694534732588551911[145] = 0; - out_8694534732588551911[146] = 0; - out_8694534732588551911[147] = 0; - out_8694534732588551911[148] = 0; - out_8694534732588551911[149] = 0; - out_8694534732588551911[150] = 0; - out_8694534732588551911[151] = 0; - out_8694534732588551911[152] = 0; - out_8694534732588551911[153] = 1.0; - out_8694534732588551911[154] = 0; - out_8694534732588551911[155] = 0; - out_8694534732588551911[156] = 0; - out_8694534732588551911[157] = 0; - out_8694534732588551911[158] = 0; - out_8694534732588551911[159] = 0; - out_8694534732588551911[160] = 0; - out_8694534732588551911[161] = 0; - out_8694534732588551911[162] = 0; - out_8694534732588551911[163] = 0; - out_8694534732588551911[164] = 0; - out_8694534732588551911[165] = 0; - out_8694534732588551911[166] = 0; - out_8694534732588551911[167] = 0; - out_8694534732588551911[168] = 0; - out_8694534732588551911[169] = 0; - out_8694534732588551911[170] = 0; - out_8694534732588551911[171] = 0; - out_8694534732588551911[172] = 0; - out_8694534732588551911[173] = 0; - out_8694534732588551911[174] = 0; - out_8694534732588551911[175] = 1.0; - out_8694534732588551911[176] = 0; - out_8694534732588551911[177] = 0; - out_8694534732588551911[178] = 0; - out_8694534732588551911[179] = 0; - out_8694534732588551911[180] = 0; - out_8694534732588551911[181] = 0; - out_8694534732588551911[182] = 0; - out_8694534732588551911[183] = 0; - out_8694534732588551911[184] = 0; - out_8694534732588551911[185] = 0; - out_8694534732588551911[186] = 0; - out_8694534732588551911[187] = 0; - out_8694534732588551911[188] = 0; - out_8694534732588551911[189] = 0; - out_8694534732588551911[190] = 0; - out_8694534732588551911[191] = 0; - out_8694534732588551911[192] = 0; - out_8694534732588551911[193] = 0; - out_8694534732588551911[194] = 0; - out_8694534732588551911[195] = 0; - out_8694534732588551911[196] = 0; - out_8694534732588551911[197] = 1.0; - out_8694534732588551911[198] = 0; - out_8694534732588551911[199] = 0; - out_8694534732588551911[200] = 0; - out_8694534732588551911[201] = 0; - out_8694534732588551911[202] = 0; - out_8694534732588551911[203] = 0; - out_8694534732588551911[204] = 0; - out_8694534732588551911[205] = 0; - out_8694534732588551911[206] = 0; - out_8694534732588551911[207] = 0; - out_8694534732588551911[208] = 0; - out_8694534732588551911[209] = 0; - out_8694534732588551911[210] = 0; - out_8694534732588551911[211] = 0; - out_8694534732588551911[212] = 0; - out_8694534732588551911[213] = 0; - out_8694534732588551911[214] = 0; - out_8694534732588551911[215] = 0; - out_8694534732588551911[216] = 0; - out_8694534732588551911[217] = 0; - out_8694534732588551911[218] = 0; - out_8694534732588551911[219] = 1.0; - out_8694534732588551911[220] = 0; - out_8694534732588551911[221] = 0; - out_8694534732588551911[222] = 0; - out_8694534732588551911[223] = 0; - out_8694534732588551911[224] = 0; - out_8694534732588551911[225] = 0; - out_8694534732588551911[226] = 0; - out_8694534732588551911[227] = 0; - out_8694534732588551911[228] = 0; - out_8694534732588551911[229] = 0; - out_8694534732588551911[230] = 0; - out_8694534732588551911[231] = 0; - out_8694534732588551911[232] = 0; - out_8694534732588551911[233] = 0; - out_8694534732588551911[234] = 0; - out_8694534732588551911[235] = 0; - out_8694534732588551911[236] = 0; - out_8694534732588551911[237] = 0; - out_8694534732588551911[238] = 0; - out_8694534732588551911[239] = 0; - out_8694534732588551911[240] = 0; - out_8694534732588551911[241] = 1.0; - out_8694534732588551911[242] = 0; - out_8694534732588551911[243] = 0; - out_8694534732588551911[244] = 0; - out_8694534732588551911[245] = 0; - out_8694534732588551911[246] = 0; - out_8694534732588551911[247] = 0; - out_8694534732588551911[248] = 0; - out_8694534732588551911[249] = 0; - out_8694534732588551911[250] = 0; - out_8694534732588551911[251] = 0; - out_8694534732588551911[252] = 0; - out_8694534732588551911[253] = 0; - out_8694534732588551911[254] = 0; - out_8694534732588551911[255] = 0; - out_8694534732588551911[256] = 0; - out_8694534732588551911[257] = 0; - out_8694534732588551911[258] = 0; - out_8694534732588551911[259] = 0; - out_8694534732588551911[260] = 0; - out_8694534732588551911[261] = 0; - out_8694534732588551911[262] = 0; - out_8694534732588551911[263] = 1.0; - out_8694534732588551911[264] = 0; - out_8694534732588551911[265] = 0; - out_8694534732588551911[266] = 0; - out_8694534732588551911[267] = 0; - out_8694534732588551911[268] = 0; - out_8694534732588551911[269] = 0; - out_8694534732588551911[270] = 0; - out_8694534732588551911[271] = 0; - out_8694534732588551911[272] = 0; - out_8694534732588551911[273] = 0; - out_8694534732588551911[274] = 0; - out_8694534732588551911[275] = 0; - out_8694534732588551911[276] = 0; - out_8694534732588551911[277] = 0; - out_8694534732588551911[278] = 0; - out_8694534732588551911[279] = 0; - out_8694534732588551911[280] = 0; - out_8694534732588551911[281] = 0; - out_8694534732588551911[282] = 0; - out_8694534732588551911[283] = 0; - out_8694534732588551911[284] = 0; - out_8694534732588551911[285] = 1.0; - out_8694534732588551911[286] = 0; - out_8694534732588551911[287] = 0; - out_8694534732588551911[288] = 0; - out_8694534732588551911[289] = 0; - out_8694534732588551911[290] = 0; - out_8694534732588551911[291] = 0; - out_8694534732588551911[292] = 0; - out_8694534732588551911[293] = 0; - out_8694534732588551911[294] = 0; - out_8694534732588551911[295] = 0; - out_8694534732588551911[296] = 0; - out_8694534732588551911[297] = 0; - out_8694534732588551911[298] = 0; - out_8694534732588551911[299] = 0; - out_8694534732588551911[300] = 0; - out_8694534732588551911[301] = 0; - out_8694534732588551911[302] = 0; - out_8694534732588551911[303] = 0; - out_8694534732588551911[304] = 0; - out_8694534732588551911[305] = 0; - out_8694534732588551911[306] = 0; - out_8694534732588551911[307] = 1.0; - out_8694534732588551911[308] = 0; - out_8694534732588551911[309] = 0; - out_8694534732588551911[310] = 0; - out_8694534732588551911[311] = 0; - out_8694534732588551911[312] = 0; - out_8694534732588551911[313] = 0; - out_8694534732588551911[314] = 0; - out_8694534732588551911[315] = 0; - out_8694534732588551911[316] = 0; - out_8694534732588551911[317] = 0; - out_8694534732588551911[318] = 0; - out_8694534732588551911[319] = 0; - out_8694534732588551911[320] = 0; - out_8694534732588551911[321] = 0; - out_8694534732588551911[322] = 0; - out_8694534732588551911[323] = 0; - out_8694534732588551911[324] = 0; - out_8694534732588551911[325] = 0; - out_8694534732588551911[326] = 0; - out_8694534732588551911[327] = 0; - out_8694534732588551911[328] = 0; - out_8694534732588551911[329] = 1.0; - out_8694534732588551911[330] = 0; - out_8694534732588551911[331] = 0; - out_8694534732588551911[332] = 0; - out_8694534732588551911[333] = 0; - out_8694534732588551911[334] = 0; - out_8694534732588551911[335] = 0; - out_8694534732588551911[336] = 0; - out_8694534732588551911[337] = 0; - out_8694534732588551911[338] = 0; - out_8694534732588551911[339] = 0; - out_8694534732588551911[340] = 0; - out_8694534732588551911[341] = 0; - out_8694534732588551911[342] = 0; - out_8694534732588551911[343] = 0; - out_8694534732588551911[344] = 0; - out_8694534732588551911[345] = 0; - out_8694534732588551911[346] = 0; - out_8694534732588551911[347] = 0; - out_8694534732588551911[348] = 0; - out_8694534732588551911[349] = 0; - out_8694534732588551911[350] = 0; - out_8694534732588551911[351] = 1.0; - out_8694534732588551911[352] = 0; - out_8694534732588551911[353] = 0; - out_8694534732588551911[354] = 0; - out_8694534732588551911[355] = 0; - out_8694534732588551911[356] = 0; - out_8694534732588551911[357] = 0; - out_8694534732588551911[358] = 0; - out_8694534732588551911[359] = 0; - out_8694534732588551911[360] = 0; - out_8694534732588551911[361] = 0; - out_8694534732588551911[362] = 0; - out_8694534732588551911[363] = 0; - out_8694534732588551911[364] = 0; - out_8694534732588551911[365] = 0; - out_8694534732588551911[366] = 0; - out_8694534732588551911[367] = 0; - out_8694534732588551911[368] = 0; - out_8694534732588551911[369] = 0; - out_8694534732588551911[370] = 0; - out_8694534732588551911[371] = 0; - out_8694534732588551911[372] = 0; - out_8694534732588551911[373] = 1.0; - out_8694534732588551911[374] = 0; - out_8694534732588551911[375] = 0; - out_8694534732588551911[376] = 0; - out_8694534732588551911[377] = 0; - out_8694534732588551911[378] = 0; - out_8694534732588551911[379] = 0; - out_8694534732588551911[380] = 0; - out_8694534732588551911[381] = 0; - out_8694534732588551911[382] = 0; - out_8694534732588551911[383] = 0; - out_8694534732588551911[384] = 0; - out_8694534732588551911[385] = 0; - out_8694534732588551911[386] = 0; - out_8694534732588551911[387] = 0; - out_8694534732588551911[388] = 0; - out_8694534732588551911[389] = 0; - out_8694534732588551911[390] = 0; - out_8694534732588551911[391] = 0; - out_8694534732588551911[392] = 0; - out_8694534732588551911[393] = 0; - out_8694534732588551911[394] = 0; - out_8694534732588551911[395] = 1.0; - out_8694534732588551911[396] = 0; - out_8694534732588551911[397] = 0; - out_8694534732588551911[398] = 0; - out_8694534732588551911[399] = 0; - out_8694534732588551911[400] = 0; - out_8694534732588551911[401] = 0; - out_8694534732588551911[402] = 0; - out_8694534732588551911[403] = 0; - out_8694534732588551911[404] = 0; - out_8694534732588551911[405] = 0; - out_8694534732588551911[406] = 0; - out_8694534732588551911[407] = 0; - out_8694534732588551911[408] = 0; - out_8694534732588551911[409] = 0; - out_8694534732588551911[410] = 0; - out_8694534732588551911[411] = 0; - out_8694534732588551911[412] = 0; - out_8694534732588551911[413] = 0; - out_8694534732588551911[414] = 0; - out_8694534732588551911[415] = 0; - out_8694534732588551911[416] = 0; - out_8694534732588551911[417] = 1.0; - out_8694534732588551911[418] = 0; - out_8694534732588551911[419] = 0; - out_8694534732588551911[420] = 0; - out_8694534732588551911[421] = 0; - out_8694534732588551911[422] = 0; - out_8694534732588551911[423] = 0; - out_8694534732588551911[424] = 0; - out_8694534732588551911[425] = 0; - out_8694534732588551911[426] = 0; - out_8694534732588551911[427] = 0; - out_8694534732588551911[428] = 0; - out_8694534732588551911[429] = 0; - out_8694534732588551911[430] = 0; - out_8694534732588551911[431] = 0; - out_8694534732588551911[432] = 0; - out_8694534732588551911[433] = 0; - out_8694534732588551911[434] = 0; - out_8694534732588551911[435] = 0; - out_8694534732588551911[436] = 0; - out_8694534732588551911[437] = 0; - out_8694534732588551911[438] = 0; - out_8694534732588551911[439] = 1.0; - out_8694534732588551911[440] = 0; - out_8694534732588551911[441] = 0; - out_8694534732588551911[442] = 0; - out_8694534732588551911[443] = 0; - out_8694534732588551911[444] = 0; - out_8694534732588551911[445] = 0; - out_8694534732588551911[446] = 0; - out_8694534732588551911[447] = 0; - out_8694534732588551911[448] = 0; - out_8694534732588551911[449] = 0; - out_8694534732588551911[450] = 0; - out_8694534732588551911[451] = 0; - out_8694534732588551911[452] = 0; - out_8694534732588551911[453] = 0; - out_8694534732588551911[454] = 0; - out_8694534732588551911[455] = 0; - out_8694534732588551911[456] = 0; - out_8694534732588551911[457] = 0; - out_8694534732588551911[458] = 0; - out_8694534732588551911[459] = 0; - out_8694534732588551911[460] = 0; - out_8694534732588551911[461] = 1.0; +void H_mod_fun(double *state, double *out_1988291488770769521) { + out_1988291488770769521[0] = 1.0; + out_1988291488770769521[1] = 0; + out_1988291488770769521[2] = 0; + out_1988291488770769521[3] = 0; + out_1988291488770769521[4] = 0; + out_1988291488770769521[5] = 0; + out_1988291488770769521[6] = 0; + out_1988291488770769521[7] = 0; + out_1988291488770769521[8] = 0; + out_1988291488770769521[9] = 0; + out_1988291488770769521[10] = 0; + out_1988291488770769521[11] = 0; + out_1988291488770769521[12] = 0; + out_1988291488770769521[13] = 0; + out_1988291488770769521[14] = 0; + out_1988291488770769521[15] = 0; + out_1988291488770769521[16] = 0; + out_1988291488770769521[17] = 0; + out_1988291488770769521[18] = 0; + out_1988291488770769521[19] = 0; + out_1988291488770769521[20] = 0; + out_1988291488770769521[21] = 0; + out_1988291488770769521[22] = 1.0; + out_1988291488770769521[23] = 0; + out_1988291488770769521[24] = 0; + out_1988291488770769521[25] = 0; + out_1988291488770769521[26] = 0; + out_1988291488770769521[27] = 0; + out_1988291488770769521[28] = 0; + out_1988291488770769521[29] = 0; + out_1988291488770769521[30] = 0; + out_1988291488770769521[31] = 0; + out_1988291488770769521[32] = 0; + out_1988291488770769521[33] = 0; + out_1988291488770769521[34] = 0; + out_1988291488770769521[35] = 0; + out_1988291488770769521[36] = 0; + out_1988291488770769521[37] = 0; + out_1988291488770769521[38] = 0; + out_1988291488770769521[39] = 0; + out_1988291488770769521[40] = 0; + out_1988291488770769521[41] = 0; + out_1988291488770769521[42] = 0; + out_1988291488770769521[43] = 0; + out_1988291488770769521[44] = 1.0; + out_1988291488770769521[45] = 0; + out_1988291488770769521[46] = 0; + out_1988291488770769521[47] = 0; + out_1988291488770769521[48] = 0; + out_1988291488770769521[49] = 0; + out_1988291488770769521[50] = 0; + out_1988291488770769521[51] = 0; + out_1988291488770769521[52] = 0; + out_1988291488770769521[53] = 0; + out_1988291488770769521[54] = 0; + out_1988291488770769521[55] = 0; + out_1988291488770769521[56] = 0; + out_1988291488770769521[57] = 0; + out_1988291488770769521[58] = 0; + out_1988291488770769521[59] = 0; + out_1988291488770769521[60] = 0; + out_1988291488770769521[61] = 0; + out_1988291488770769521[62] = 0; + out_1988291488770769521[63] = 0; + out_1988291488770769521[64] = 0; + out_1988291488770769521[65] = 0; + out_1988291488770769521[66] = -0.5*state[4]; + out_1988291488770769521[67] = -0.5*state[5]; + out_1988291488770769521[68] = -0.5*state[6]; + out_1988291488770769521[69] = 0; + out_1988291488770769521[70] = 0; + out_1988291488770769521[71] = 0; + out_1988291488770769521[72] = 0; + out_1988291488770769521[73] = 0; + out_1988291488770769521[74] = 0; + out_1988291488770769521[75] = 0; + out_1988291488770769521[76] = 0; + out_1988291488770769521[77] = 0; + out_1988291488770769521[78] = 0; + out_1988291488770769521[79] = 0; + out_1988291488770769521[80] = 0; + out_1988291488770769521[81] = 0; + out_1988291488770769521[82] = 0; + out_1988291488770769521[83] = 0; + out_1988291488770769521[84] = 0; + out_1988291488770769521[85] = 0; + out_1988291488770769521[86] = 0; + out_1988291488770769521[87] = 0.5*state[3]; + out_1988291488770769521[88] = 0.5*state[6]; + out_1988291488770769521[89] = -0.5*state[5]; + out_1988291488770769521[90] = 0; + out_1988291488770769521[91] = 0; + out_1988291488770769521[92] = 0; + out_1988291488770769521[93] = 0; + out_1988291488770769521[94] = 0; + out_1988291488770769521[95] = 0; + out_1988291488770769521[96] = 0; + out_1988291488770769521[97] = 0; + out_1988291488770769521[98] = 0; + out_1988291488770769521[99] = 0; + out_1988291488770769521[100] = 0; + out_1988291488770769521[101] = 0; + out_1988291488770769521[102] = 0; + out_1988291488770769521[103] = 0; + out_1988291488770769521[104] = 0; + out_1988291488770769521[105] = 0; + out_1988291488770769521[106] = 0; + out_1988291488770769521[107] = 0; + out_1988291488770769521[108] = -0.5*state[6]; + out_1988291488770769521[109] = 0.5*state[3]; + out_1988291488770769521[110] = 0.5*state[4]; + out_1988291488770769521[111] = 0; + out_1988291488770769521[112] = 0; + out_1988291488770769521[113] = 0; + out_1988291488770769521[114] = 0; + out_1988291488770769521[115] = 0; + out_1988291488770769521[116] = 0; + out_1988291488770769521[117] = 0; + out_1988291488770769521[118] = 0; + out_1988291488770769521[119] = 0; + out_1988291488770769521[120] = 0; + out_1988291488770769521[121] = 0; + out_1988291488770769521[122] = 0; + out_1988291488770769521[123] = 0; + out_1988291488770769521[124] = 0; + out_1988291488770769521[125] = 0; + out_1988291488770769521[126] = 0; + out_1988291488770769521[127] = 0; + out_1988291488770769521[128] = 0; + out_1988291488770769521[129] = 0.5*state[5]; + out_1988291488770769521[130] = -0.5*state[4]; + out_1988291488770769521[131] = 0.5*state[3]; + out_1988291488770769521[132] = 0; + out_1988291488770769521[133] = 0; + out_1988291488770769521[134] = 0; + out_1988291488770769521[135] = 0; + out_1988291488770769521[136] = 0; + out_1988291488770769521[137] = 0; + out_1988291488770769521[138] = 0; + out_1988291488770769521[139] = 0; + out_1988291488770769521[140] = 0; + out_1988291488770769521[141] = 0; + out_1988291488770769521[142] = 0; + out_1988291488770769521[143] = 0; + out_1988291488770769521[144] = 0; + out_1988291488770769521[145] = 0; + out_1988291488770769521[146] = 0; + out_1988291488770769521[147] = 0; + out_1988291488770769521[148] = 0; + out_1988291488770769521[149] = 0; + out_1988291488770769521[150] = 0; + out_1988291488770769521[151] = 0; + out_1988291488770769521[152] = 0; + out_1988291488770769521[153] = 1.0; + out_1988291488770769521[154] = 0; + out_1988291488770769521[155] = 0; + out_1988291488770769521[156] = 0; + out_1988291488770769521[157] = 0; + out_1988291488770769521[158] = 0; + out_1988291488770769521[159] = 0; + out_1988291488770769521[160] = 0; + out_1988291488770769521[161] = 0; + out_1988291488770769521[162] = 0; + out_1988291488770769521[163] = 0; + out_1988291488770769521[164] = 0; + out_1988291488770769521[165] = 0; + out_1988291488770769521[166] = 0; + out_1988291488770769521[167] = 0; + out_1988291488770769521[168] = 0; + out_1988291488770769521[169] = 0; + out_1988291488770769521[170] = 0; + out_1988291488770769521[171] = 0; + out_1988291488770769521[172] = 0; + out_1988291488770769521[173] = 0; + out_1988291488770769521[174] = 0; + out_1988291488770769521[175] = 1.0; + out_1988291488770769521[176] = 0; + out_1988291488770769521[177] = 0; + out_1988291488770769521[178] = 0; + out_1988291488770769521[179] = 0; + out_1988291488770769521[180] = 0; + out_1988291488770769521[181] = 0; + out_1988291488770769521[182] = 0; + out_1988291488770769521[183] = 0; + out_1988291488770769521[184] = 0; + out_1988291488770769521[185] = 0; + out_1988291488770769521[186] = 0; + out_1988291488770769521[187] = 0; + out_1988291488770769521[188] = 0; + out_1988291488770769521[189] = 0; + out_1988291488770769521[190] = 0; + out_1988291488770769521[191] = 0; + out_1988291488770769521[192] = 0; + out_1988291488770769521[193] = 0; + out_1988291488770769521[194] = 0; + out_1988291488770769521[195] = 0; + out_1988291488770769521[196] = 0; + out_1988291488770769521[197] = 1.0; + out_1988291488770769521[198] = 0; + out_1988291488770769521[199] = 0; + out_1988291488770769521[200] = 0; + out_1988291488770769521[201] = 0; + out_1988291488770769521[202] = 0; + out_1988291488770769521[203] = 0; + out_1988291488770769521[204] = 0; + out_1988291488770769521[205] = 0; + out_1988291488770769521[206] = 0; + out_1988291488770769521[207] = 0; + out_1988291488770769521[208] = 0; + out_1988291488770769521[209] = 0; + out_1988291488770769521[210] = 0; + out_1988291488770769521[211] = 0; + out_1988291488770769521[212] = 0; + out_1988291488770769521[213] = 0; + out_1988291488770769521[214] = 0; + out_1988291488770769521[215] = 0; + out_1988291488770769521[216] = 0; + out_1988291488770769521[217] = 0; + out_1988291488770769521[218] = 0; + out_1988291488770769521[219] = 1.0; + out_1988291488770769521[220] = 0; + out_1988291488770769521[221] = 0; + out_1988291488770769521[222] = 0; + out_1988291488770769521[223] = 0; + out_1988291488770769521[224] = 0; + out_1988291488770769521[225] = 0; + out_1988291488770769521[226] = 0; + out_1988291488770769521[227] = 0; + out_1988291488770769521[228] = 0; + out_1988291488770769521[229] = 0; + out_1988291488770769521[230] = 0; + out_1988291488770769521[231] = 0; + out_1988291488770769521[232] = 0; + out_1988291488770769521[233] = 0; + out_1988291488770769521[234] = 0; + out_1988291488770769521[235] = 0; + out_1988291488770769521[236] = 0; + out_1988291488770769521[237] = 0; + out_1988291488770769521[238] = 0; + out_1988291488770769521[239] = 0; + out_1988291488770769521[240] = 0; + out_1988291488770769521[241] = 1.0; + out_1988291488770769521[242] = 0; + out_1988291488770769521[243] = 0; + out_1988291488770769521[244] = 0; + out_1988291488770769521[245] = 0; + out_1988291488770769521[246] = 0; + out_1988291488770769521[247] = 0; + out_1988291488770769521[248] = 0; + out_1988291488770769521[249] = 0; + out_1988291488770769521[250] = 0; + out_1988291488770769521[251] = 0; + out_1988291488770769521[252] = 0; + out_1988291488770769521[253] = 0; + out_1988291488770769521[254] = 0; + out_1988291488770769521[255] = 0; + out_1988291488770769521[256] = 0; + out_1988291488770769521[257] = 0; + out_1988291488770769521[258] = 0; + out_1988291488770769521[259] = 0; + out_1988291488770769521[260] = 0; + out_1988291488770769521[261] = 0; + out_1988291488770769521[262] = 0; + out_1988291488770769521[263] = 1.0; + out_1988291488770769521[264] = 0; + out_1988291488770769521[265] = 0; + out_1988291488770769521[266] = 0; + out_1988291488770769521[267] = 0; + out_1988291488770769521[268] = 0; + out_1988291488770769521[269] = 0; + out_1988291488770769521[270] = 0; + out_1988291488770769521[271] = 0; + out_1988291488770769521[272] = 0; + out_1988291488770769521[273] = 0; + out_1988291488770769521[274] = 0; + out_1988291488770769521[275] = 0; + out_1988291488770769521[276] = 0; + out_1988291488770769521[277] = 0; + out_1988291488770769521[278] = 0; + out_1988291488770769521[279] = 0; + out_1988291488770769521[280] = 0; + out_1988291488770769521[281] = 0; + out_1988291488770769521[282] = 0; + out_1988291488770769521[283] = 0; + out_1988291488770769521[284] = 0; + out_1988291488770769521[285] = 1.0; + out_1988291488770769521[286] = 0; + out_1988291488770769521[287] = 0; + out_1988291488770769521[288] = 0; + out_1988291488770769521[289] = 0; + out_1988291488770769521[290] = 0; + out_1988291488770769521[291] = 0; + out_1988291488770769521[292] = 0; + out_1988291488770769521[293] = 0; + out_1988291488770769521[294] = 0; + out_1988291488770769521[295] = 0; + out_1988291488770769521[296] = 0; + out_1988291488770769521[297] = 0; + out_1988291488770769521[298] = 0; + out_1988291488770769521[299] = 0; + out_1988291488770769521[300] = 0; + out_1988291488770769521[301] = 0; + out_1988291488770769521[302] = 0; + out_1988291488770769521[303] = 0; + out_1988291488770769521[304] = 0; + out_1988291488770769521[305] = 0; + out_1988291488770769521[306] = 0; + out_1988291488770769521[307] = 1.0; + out_1988291488770769521[308] = 0; + out_1988291488770769521[309] = 0; + out_1988291488770769521[310] = 0; + out_1988291488770769521[311] = 0; + out_1988291488770769521[312] = 0; + out_1988291488770769521[313] = 0; + out_1988291488770769521[314] = 0; + out_1988291488770769521[315] = 0; + out_1988291488770769521[316] = 0; + out_1988291488770769521[317] = 0; + out_1988291488770769521[318] = 0; + out_1988291488770769521[319] = 0; + out_1988291488770769521[320] = 0; + out_1988291488770769521[321] = 0; + out_1988291488770769521[322] = 0; + out_1988291488770769521[323] = 0; + out_1988291488770769521[324] = 0; + out_1988291488770769521[325] = 0; + out_1988291488770769521[326] = 0; + out_1988291488770769521[327] = 0; + out_1988291488770769521[328] = 0; + out_1988291488770769521[329] = 1.0; + out_1988291488770769521[330] = 0; + out_1988291488770769521[331] = 0; + out_1988291488770769521[332] = 0; + out_1988291488770769521[333] = 0; + out_1988291488770769521[334] = 0; + out_1988291488770769521[335] = 0; + out_1988291488770769521[336] = 0; + out_1988291488770769521[337] = 0; + out_1988291488770769521[338] = 0; + out_1988291488770769521[339] = 0; + out_1988291488770769521[340] = 0; + out_1988291488770769521[341] = 0; + out_1988291488770769521[342] = 0; + out_1988291488770769521[343] = 0; + out_1988291488770769521[344] = 0; + out_1988291488770769521[345] = 0; + out_1988291488770769521[346] = 0; + out_1988291488770769521[347] = 0; + out_1988291488770769521[348] = 0; + out_1988291488770769521[349] = 0; + out_1988291488770769521[350] = 0; + out_1988291488770769521[351] = 1.0; + out_1988291488770769521[352] = 0; + out_1988291488770769521[353] = 0; + out_1988291488770769521[354] = 0; + out_1988291488770769521[355] = 0; + out_1988291488770769521[356] = 0; + out_1988291488770769521[357] = 0; + out_1988291488770769521[358] = 0; + out_1988291488770769521[359] = 0; + out_1988291488770769521[360] = 0; + out_1988291488770769521[361] = 0; + out_1988291488770769521[362] = 0; + out_1988291488770769521[363] = 0; + out_1988291488770769521[364] = 0; + out_1988291488770769521[365] = 0; + out_1988291488770769521[366] = 0; + out_1988291488770769521[367] = 0; + out_1988291488770769521[368] = 0; + out_1988291488770769521[369] = 0; + out_1988291488770769521[370] = 0; + out_1988291488770769521[371] = 0; + out_1988291488770769521[372] = 0; + out_1988291488770769521[373] = 1.0; + out_1988291488770769521[374] = 0; + out_1988291488770769521[375] = 0; + out_1988291488770769521[376] = 0; + out_1988291488770769521[377] = 0; + out_1988291488770769521[378] = 0; + out_1988291488770769521[379] = 0; + out_1988291488770769521[380] = 0; + out_1988291488770769521[381] = 0; + out_1988291488770769521[382] = 0; + out_1988291488770769521[383] = 0; + out_1988291488770769521[384] = 0; + out_1988291488770769521[385] = 0; + out_1988291488770769521[386] = 0; + out_1988291488770769521[387] = 0; + out_1988291488770769521[388] = 0; + out_1988291488770769521[389] = 0; + out_1988291488770769521[390] = 0; + out_1988291488770769521[391] = 0; + out_1988291488770769521[392] = 0; + out_1988291488770769521[393] = 0; + out_1988291488770769521[394] = 0; + out_1988291488770769521[395] = 1.0; + out_1988291488770769521[396] = 0; + out_1988291488770769521[397] = 0; + out_1988291488770769521[398] = 0; + out_1988291488770769521[399] = 0; + out_1988291488770769521[400] = 0; + out_1988291488770769521[401] = 0; + out_1988291488770769521[402] = 0; + out_1988291488770769521[403] = 0; + out_1988291488770769521[404] = 0; + out_1988291488770769521[405] = 0; + out_1988291488770769521[406] = 0; + out_1988291488770769521[407] = 0; + out_1988291488770769521[408] = 0; + out_1988291488770769521[409] = 0; + out_1988291488770769521[410] = 0; + out_1988291488770769521[411] = 0; + out_1988291488770769521[412] = 0; + out_1988291488770769521[413] = 0; + out_1988291488770769521[414] = 0; + out_1988291488770769521[415] = 0; + out_1988291488770769521[416] = 0; + out_1988291488770769521[417] = 1.0; + out_1988291488770769521[418] = 0; + out_1988291488770769521[419] = 0; + out_1988291488770769521[420] = 0; + out_1988291488770769521[421] = 0; + out_1988291488770769521[422] = 0; + out_1988291488770769521[423] = 0; + out_1988291488770769521[424] = 0; + out_1988291488770769521[425] = 0; + out_1988291488770769521[426] = 0; + out_1988291488770769521[427] = 0; + out_1988291488770769521[428] = 0; + out_1988291488770769521[429] = 0; + out_1988291488770769521[430] = 0; + out_1988291488770769521[431] = 0; + out_1988291488770769521[432] = 0; + out_1988291488770769521[433] = 0; + out_1988291488770769521[434] = 0; + out_1988291488770769521[435] = 0; + out_1988291488770769521[436] = 0; + out_1988291488770769521[437] = 0; + out_1988291488770769521[438] = 0; + out_1988291488770769521[439] = 1.0; + out_1988291488770769521[440] = 0; + out_1988291488770769521[441] = 0; + out_1988291488770769521[442] = 0; + out_1988291488770769521[443] = 0; + out_1988291488770769521[444] = 0; + out_1988291488770769521[445] = 0; + out_1988291488770769521[446] = 0; + out_1988291488770769521[447] = 0; + out_1988291488770769521[448] = 0; + out_1988291488770769521[449] = 0; + out_1988291488770769521[450] = 0; + out_1988291488770769521[451] = 0; + out_1988291488770769521[452] = 0; + out_1988291488770769521[453] = 0; + out_1988291488770769521[454] = 0; + out_1988291488770769521[455] = 0; + out_1988291488770769521[456] = 0; + out_1988291488770769521[457] = 0; + out_1988291488770769521[458] = 0; + out_1988291488770769521[459] = 0; + out_1988291488770769521[460] = 0; + out_1988291488770769521[461] = 1.0; } -void f_fun(double *state, double dt, double *out_331980123976991440) { - out_331980123976991440[0] = dt*state[7] + state[0]; - out_331980123976991440[1] = dt*state[8] + state[1]; - out_331980123976991440[2] = dt*state[9] + state[2]; - out_331980123976991440[3] = dt*(-0.5*state[4]*state[10] - 0.5*state[5]*state[11] - 0.5*state[6]*state[12]) + state[3]; - out_331980123976991440[4] = dt*(0.5*state[3]*state[10] + 0.5*state[5]*state[12] - 0.5*state[6]*state[11]) + state[4]; - out_331980123976991440[5] = dt*(0.5*state[3]*state[11] - 0.5*state[4]*state[12] + 0.5*state[6]*state[10]) + state[5]; - out_331980123976991440[6] = dt*(0.5*state[3]*state[12] + 0.5*state[4]*state[11] - 0.5*state[5]*state[10]) + state[6]; - out_331980123976991440[7] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]) + state[7]; - out_331980123976991440[8] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]) + state[8]; - out_331980123976991440[9] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]) + state[9]; - out_331980123976991440[10] = state[10]; - out_331980123976991440[11] = state[11]; - out_331980123976991440[12] = state[12]; - out_331980123976991440[13] = state[13]; - out_331980123976991440[14] = state[14]; - out_331980123976991440[15] = state[15]; - out_331980123976991440[16] = state[16]; - out_331980123976991440[17] = state[17]; - out_331980123976991440[18] = state[18]; - out_331980123976991440[19] = state[19]; - out_331980123976991440[20] = state[20]; - out_331980123976991440[21] = state[21]; +void f_fun(double *state, double dt, double *out_3263988285527381505) { + out_3263988285527381505[0] = dt*state[7] + state[0]; + out_3263988285527381505[1] = dt*state[8] + state[1]; + out_3263988285527381505[2] = dt*state[9] + state[2]; + out_3263988285527381505[3] = dt*(-0.5*state[4]*state[10] - 0.5*state[5]*state[11] - 0.5*state[6]*state[12]) + state[3]; + out_3263988285527381505[4] = dt*(0.5*state[3]*state[10] + 0.5*state[5]*state[12] - 0.5*state[6]*state[11]) + state[4]; + out_3263988285527381505[5] = dt*(0.5*state[3]*state[11] - 0.5*state[4]*state[12] + 0.5*state[6]*state[10]) + state[5]; + out_3263988285527381505[6] = dt*(0.5*state[3]*state[12] + 0.5*state[4]*state[11] - 0.5*state[5]*state[10]) + state[6]; + out_3263988285527381505[7] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]) + state[7]; + out_3263988285527381505[8] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]) + state[8]; + out_3263988285527381505[9] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]) + state[9]; + out_3263988285527381505[10] = state[10]; + out_3263988285527381505[11] = state[11]; + out_3263988285527381505[12] = state[12]; + out_3263988285527381505[13] = state[13]; + out_3263988285527381505[14] = state[14]; + out_3263988285527381505[15] = state[15]; + out_3263988285527381505[16] = state[16]; + out_3263988285527381505[17] = state[17]; + out_3263988285527381505[18] = state[18]; + out_3263988285527381505[19] = state[19]; + out_3263988285527381505[20] = state[20]; + out_3263988285527381505[21] = state[21]; } -void F_fun(double *state, double dt, double *out_7523521905118560137) { - out_7523521905118560137[0] = 1; - out_7523521905118560137[1] = 0; - out_7523521905118560137[2] = 0; - out_7523521905118560137[3] = 0; - out_7523521905118560137[4] = 0; - out_7523521905118560137[5] = 0; - out_7523521905118560137[6] = dt; - out_7523521905118560137[7] = 0; - out_7523521905118560137[8] = 0; - out_7523521905118560137[9] = 0; - out_7523521905118560137[10] = 0; - out_7523521905118560137[11] = 0; - out_7523521905118560137[12] = 0; - out_7523521905118560137[13] = 0; - out_7523521905118560137[14] = 0; - out_7523521905118560137[15] = 0; - out_7523521905118560137[16] = 0; - out_7523521905118560137[17] = 0; - out_7523521905118560137[18] = 0; - out_7523521905118560137[19] = 0; - out_7523521905118560137[20] = 0; - out_7523521905118560137[21] = 0; - out_7523521905118560137[22] = 1; - out_7523521905118560137[23] = 0; - out_7523521905118560137[24] = 0; - out_7523521905118560137[25] = 0; - out_7523521905118560137[26] = 0; - out_7523521905118560137[27] = 0; - out_7523521905118560137[28] = dt; - out_7523521905118560137[29] = 0; - out_7523521905118560137[30] = 0; - out_7523521905118560137[31] = 0; - out_7523521905118560137[32] = 0; - out_7523521905118560137[33] = 0; - out_7523521905118560137[34] = 0; - out_7523521905118560137[35] = 0; - out_7523521905118560137[36] = 0; - out_7523521905118560137[37] = 0; - out_7523521905118560137[38] = 0; - out_7523521905118560137[39] = 0; - out_7523521905118560137[40] = 0; - out_7523521905118560137[41] = 0; - out_7523521905118560137[42] = 0; - out_7523521905118560137[43] = 0; - out_7523521905118560137[44] = 1; - out_7523521905118560137[45] = 0; - out_7523521905118560137[46] = 0; - out_7523521905118560137[47] = 0; - out_7523521905118560137[48] = 0; - out_7523521905118560137[49] = 0; - out_7523521905118560137[50] = dt; - out_7523521905118560137[51] = 0; - out_7523521905118560137[52] = 0; - out_7523521905118560137[53] = 0; - out_7523521905118560137[54] = 0; - out_7523521905118560137[55] = 0; - out_7523521905118560137[56] = 0; - out_7523521905118560137[57] = 0; - out_7523521905118560137[58] = 0; - out_7523521905118560137[59] = 0; - out_7523521905118560137[60] = 0; - out_7523521905118560137[61] = 0; - out_7523521905118560137[62] = 0; - out_7523521905118560137[63] = 0; - out_7523521905118560137[64] = 0; - out_7523521905118560137[65] = 0; - out_7523521905118560137[66] = 1; - out_7523521905118560137[67] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[11] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); - out_7523521905118560137[68] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[12] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[10] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[11]); - out_7523521905118560137[69] = 0; - out_7523521905118560137[70] = 0; - out_7523521905118560137[71] = 0; - out_7523521905118560137[72] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_7523521905118560137[73] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); - out_7523521905118560137[74] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); - out_7523521905118560137[75] = 0; - out_7523521905118560137[76] = 0; - out_7523521905118560137[77] = 0; - out_7523521905118560137[78] = 0; - out_7523521905118560137[79] = 0; - out_7523521905118560137[80] = 0; - out_7523521905118560137[81] = 0; - out_7523521905118560137[82] = 0; - out_7523521905118560137[83] = 0; - out_7523521905118560137[84] = 0; - out_7523521905118560137[85] = 0; - out_7523521905118560137[86] = 0; - out_7523521905118560137[87] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[11] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); - out_7523521905118560137[88] = 1; - out_7523521905118560137[89] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[12] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[11] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[10]); - out_7523521905118560137[90] = 0; - out_7523521905118560137[91] = 0; - out_7523521905118560137[92] = 0; - out_7523521905118560137[93] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); - out_7523521905118560137[94] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_7523521905118560137[95] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); - out_7523521905118560137[96] = 0; - out_7523521905118560137[97] = 0; - out_7523521905118560137[98] = 0; - out_7523521905118560137[99] = 0; - out_7523521905118560137[100] = 0; - out_7523521905118560137[101] = 0; - out_7523521905118560137[102] = 0; - out_7523521905118560137[103] = 0; - out_7523521905118560137[104] = 0; - out_7523521905118560137[105] = 0; - out_7523521905118560137[106] = 0; - out_7523521905118560137[107] = 0; - out_7523521905118560137[108] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[12] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[10] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[11]); - out_7523521905118560137[109] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[12] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[11] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[10]); - out_7523521905118560137[110] = 1; - out_7523521905118560137[111] = 0; - out_7523521905118560137[112] = 0; - out_7523521905118560137[113] = 0; - out_7523521905118560137[114] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); - out_7523521905118560137[115] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); - out_7523521905118560137[116] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_7523521905118560137[117] = 0; - out_7523521905118560137[118] = 0; - out_7523521905118560137[119] = 0; - out_7523521905118560137[120] = 0; - out_7523521905118560137[121] = 0; - out_7523521905118560137[122] = 0; - out_7523521905118560137[123] = 0; - out_7523521905118560137[124] = 0; - out_7523521905118560137[125] = 0; - out_7523521905118560137[126] = 0; - out_7523521905118560137[127] = 0; - out_7523521905118560137[128] = 0; - out_7523521905118560137[129] = 0; - out_7523521905118560137[130] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); - out_7523521905118560137[131] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[18] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[16] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[17]); - out_7523521905118560137[132] = 1; - out_7523521905118560137[133] = 0; - out_7523521905118560137[134] = 0; - out_7523521905118560137[135] = 0; - out_7523521905118560137[136] = 0; - out_7523521905118560137[137] = 0; - out_7523521905118560137[138] = 0; - out_7523521905118560137[139] = 0; - out_7523521905118560137[140] = 0; - out_7523521905118560137[141] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_7523521905118560137[142] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); - out_7523521905118560137[143] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); - out_7523521905118560137[144] = 0; - out_7523521905118560137[145] = 0; - out_7523521905118560137[146] = 0; - out_7523521905118560137[147] = 0; - out_7523521905118560137[148] = 0; - out_7523521905118560137[149] = 0; - out_7523521905118560137[150] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[17] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); - out_7523521905118560137[151] = 0; - out_7523521905118560137[152] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]); - out_7523521905118560137[153] = 0; - out_7523521905118560137[154] = 1; - out_7523521905118560137[155] = 0; - out_7523521905118560137[156] = 0; - out_7523521905118560137[157] = 0; - out_7523521905118560137[158] = 0; - out_7523521905118560137[159] = 0; - out_7523521905118560137[160] = 0; - out_7523521905118560137[161] = 0; - out_7523521905118560137[162] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); - out_7523521905118560137[163] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_7523521905118560137[164] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); - out_7523521905118560137[165] = 0; - out_7523521905118560137[166] = 0; - out_7523521905118560137[167] = 0; - out_7523521905118560137[168] = 0; - out_7523521905118560137[169] = 0; - out_7523521905118560137[170] = 0; - out_7523521905118560137[171] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]); - out_7523521905118560137[172] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[18] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[17] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[16]); - out_7523521905118560137[173] = 0; - out_7523521905118560137[174] = 0; - out_7523521905118560137[175] = 0; - out_7523521905118560137[176] = 1; - out_7523521905118560137[177] = 0; - out_7523521905118560137[178] = 0; - out_7523521905118560137[179] = 0; - out_7523521905118560137[180] = 0; - out_7523521905118560137[181] = 0; - out_7523521905118560137[182] = 0; - out_7523521905118560137[183] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); - out_7523521905118560137[184] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); - out_7523521905118560137[185] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_7523521905118560137[186] = 0; - out_7523521905118560137[187] = 0; - out_7523521905118560137[188] = 0; - out_7523521905118560137[189] = 0; - out_7523521905118560137[190] = 0; - out_7523521905118560137[191] = 0; - out_7523521905118560137[192] = 0; - out_7523521905118560137[193] = 0; - out_7523521905118560137[194] = 0; - out_7523521905118560137[195] = 0; - out_7523521905118560137[196] = 0; - out_7523521905118560137[197] = 0; - out_7523521905118560137[198] = 1; - out_7523521905118560137[199] = 0; - out_7523521905118560137[200] = 0; - out_7523521905118560137[201] = 0; - out_7523521905118560137[202] = 0; - out_7523521905118560137[203] = 0; - out_7523521905118560137[204] = 0; - out_7523521905118560137[205] = 0; - out_7523521905118560137[206] = 0; - out_7523521905118560137[207] = 0; - out_7523521905118560137[208] = 0; - out_7523521905118560137[209] = 0; - out_7523521905118560137[210] = 0; - out_7523521905118560137[211] = 0; - out_7523521905118560137[212] = 0; - out_7523521905118560137[213] = 0; - out_7523521905118560137[214] = 0; - out_7523521905118560137[215] = 0; - out_7523521905118560137[216] = 0; - out_7523521905118560137[217] = 0; - out_7523521905118560137[218] = 0; - out_7523521905118560137[219] = 0; - out_7523521905118560137[220] = 1; - out_7523521905118560137[221] = 0; - out_7523521905118560137[222] = 0; - out_7523521905118560137[223] = 0; - out_7523521905118560137[224] = 0; - out_7523521905118560137[225] = 0; - out_7523521905118560137[226] = 0; - out_7523521905118560137[227] = 0; - out_7523521905118560137[228] = 0; - out_7523521905118560137[229] = 0; - out_7523521905118560137[230] = 0; - out_7523521905118560137[231] = 0; - out_7523521905118560137[232] = 0; - out_7523521905118560137[233] = 0; - out_7523521905118560137[234] = 0; - out_7523521905118560137[235] = 0; - out_7523521905118560137[236] = 0; - out_7523521905118560137[237] = 0; - out_7523521905118560137[238] = 0; - out_7523521905118560137[239] = 0; - out_7523521905118560137[240] = 0; - out_7523521905118560137[241] = 0; - out_7523521905118560137[242] = 1; - out_7523521905118560137[243] = 0; - out_7523521905118560137[244] = 0; - out_7523521905118560137[245] = 0; - out_7523521905118560137[246] = 0; - out_7523521905118560137[247] = 0; - out_7523521905118560137[248] = 0; - out_7523521905118560137[249] = 0; - out_7523521905118560137[250] = 0; - out_7523521905118560137[251] = 0; - out_7523521905118560137[252] = 0; - out_7523521905118560137[253] = 0; - out_7523521905118560137[254] = 0; - out_7523521905118560137[255] = 0; - out_7523521905118560137[256] = 0; - out_7523521905118560137[257] = 0; - out_7523521905118560137[258] = 0; - out_7523521905118560137[259] = 0; - out_7523521905118560137[260] = 0; - out_7523521905118560137[261] = 0; - out_7523521905118560137[262] = 0; - out_7523521905118560137[263] = 0; - out_7523521905118560137[264] = 1; - out_7523521905118560137[265] = 0; - out_7523521905118560137[266] = 0; - out_7523521905118560137[267] = 0; - out_7523521905118560137[268] = 0; - out_7523521905118560137[269] = 0; - out_7523521905118560137[270] = 0; - out_7523521905118560137[271] = 0; - out_7523521905118560137[272] = 0; - out_7523521905118560137[273] = 0; - out_7523521905118560137[274] = 0; - out_7523521905118560137[275] = 0; - out_7523521905118560137[276] = 0; - out_7523521905118560137[277] = 0; - out_7523521905118560137[278] = 0; - out_7523521905118560137[279] = 0; - out_7523521905118560137[280] = 0; - out_7523521905118560137[281] = 0; - out_7523521905118560137[282] = 0; - out_7523521905118560137[283] = 0; - out_7523521905118560137[284] = 0; - out_7523521905118560137[285] = 0; - out_7523521905118560137[286] = 1; - out_7523521905118560137[287] = 0; - out_7523521905118560137[288] = 0; - out_7523521905118560137[289] = 0; - out_7523521905118560137[290] = 0; - out_7523521905118560137[291] = 0; - out_7523521905118560137[292] = 0; - out_7523521905118560137[293] = 0; - out_7523521905118560137[294] = 0; - out_7523521905118560137[295] = 0; - out_7523521905118560137[296] = 0; - out_7523521905118560137[297] = 0; - out_7523521905118560137[298] = 0; - out_7523521905118560137[299] = 0; - out_7523521905118560137[300] = 0; - out_7523521905118560137[301] = 0; - out_7523521905118560137[302] = 0; - out_7523521905118560137[303] = 0; - out_7523521905118560137[304] = 0; - out_7523521905118560137[305] = 0; - out_7523521905118560137[306] = 0; - out_7523521905118560137[307] = 0; - out_7523521905118560137[308] = 1; - out_7523521905118560137[309] = 0; - out_7523521905118560137[310] = 0; - out_7523521905118560137[311] = 0; - out_7523521905118560137[312] = 0; - out_7523521905118560137[313] = 0; - out_7523521905118560137[314] = 0; - out_7523521905118560137[315] = 0; - out_7523521905118560137[316] = 0; - out_7523521905118560137[317] = 0; - out_7523521905118560137[318] = 0; - out_7523521905118560137[319] = 0; - out_7523521905118560137[320] = 0; - out_7523521905118560137[321] = 0; - out_7523521905118560137[322] = 0; - out_7523521905118560137[323] = 0; - out_7523521905118560137[324] = 0; - out_7523521905118560137[325] = 0; - out_7523521905118560137[326] = 0; - out_7523521905118560137[327] = 0; - out_7523521905118560137[328] = 0; - out_7523521905118560137[329] = 0; - out_7523521905118560137[330] = 1; - out_7523521905118560137[331] = 0; - out_7523521905118560137[332] = 0; - out_7523521905118560137[333] = 0; - out_7523521905118560137[334] = 0; - out_7523521905118560137[335] = 0; - out_7523521905118560137[336] = 0; - out_7523521905118560137[337] = 0; - out_7523521905118560137[338] = 0; - out_7523521905118560137[339] = 0; - out_7523521905118560137[340] = 0; - out_7523521905118560137[341] = 0; - out_7523521905118560137[342] = 0; - out_7523521905118560137[343] = 0; - out_7523521905118560137[344] = 0; - out_7523521905118560137[345] = 0; - out_7523521905118560137[346] = 0; - out_7523521905118560137[347] = 0; - out_7523521905118560137[348] = 0; - out_7523521905118560137[349] = 0; - out_7523521905118560137[350] = 0; - out_7523521905118560137[351] = 0; - out_7523521905118560137[352] = 1; - out_7523521905118560137[353] = 0; - out_7523521905118560137[354] = 0; - out_7523521905118560137[355] = 0; - out_7523521905118560137[356] = 0; - out_7523521905118560137[357] = 0; - out_7523521905118560137[358] = 0; - out_7523521905118560137[359] = 0; - out_7523521905118560137[360] = 0; - out_7523521905118560137[361] = 0; - out_7523521905118560137[362] = 0; - out_7523521905118560137[363] = 0; - out_7523521905118560137[364] = 0; - out_7523521905118560137[365] = 0; - out_7523521905118560137[366] = 0; - out_7523521905118560137[367] = 0; - out_7523521905118560137[368] = 0; - out_7523521905118560137[369] = 0; - out_7523521905118560137[370] = 0; - out_7523521905118560137[371] = 0; - out_7523521905118560137[372] = 0; - out_7523521905118560137[373] = 0; - out_7523521905118560137[374] = 1; - out_7523521905118560137[375] = 0; - out_7523521905118560137[376] = 0; - out_7523521905118560137[377] = 0; - out_7523521905118560137[378] = 0; - out_7523521905118560137[379] = 0; - out_7523521905118560137[380] = 0; - out_7523521905118560137[381] = 0; - out_7523521905118560137[382] = 0; - out_7523521905118560137[383] = 0; - out_7523521905118560137[384] = 0; - out_7523521905118560137[385] = 0; - out_7523521905118560137[386] = 0; - out_7523521905118560137[387] = 0; - out_7523521905118560137[388] = 0; - out_7523521905118560137[389] = 0; - out_7523521905118560137[390] = 0; - out_7523521905118560137[391] = 0; - out_7523521905118560137[392] = 0; - out_7523521905118560137[393] = 0; - out_7523521905118560137[394] = 0; - out_7523521905118560137[395] = 0; - out_7523521905118560137[396] = 1; - out_7523521905118560137[397] = 0; - out_7523521905118560137[398] = 0; - out_7523521905118560137[399] = 0; - out_7523521905118560137[400] = 0; - out_7523521905118560137[401] = 0; - out_7523521905118560137[402] = 0; - out_7523521905118560137[403] = 0; - out_7523521905118560137[404] = 0; - out_7523521905118560137[405] = 0; - out_7523521905118560137[406] = 0; - out_7523521905118560137[407] = 0; - out_7523521905118560137[408] = 0; - out_7523521905118560137[409] = 0; - out_7523521905118560137[410] = 0; - out_7523521905118560137[411] = 0; - out_7523521905118560137[412] = 0; - out_7523521905118560137[413] = 0; - out_7523521905118560137[414] = 0; - out_7523521905118560137[415] = 0; - out_7523521905118560137[416] = 0; - out_7523521905118560137[417] = 0; - out_7523521905118560137[418] = 1; - out_7523521905118560137[419] = 0; - out_7523521905118560137[420] = 0; - out_7523521905118560137[421] = 0; - out_7523521905118560137[422] = 0; - out_7523521905118560137[423] = 0; - out_7523521905118560137[424] = 0; - out_7523521905118560137[425] = 0; - out_7523521905118560137[426] = 0; - out_7523521905118560137[427] = 0; - out_7523521905118560137[428] = 0; - out_7523521905118560137[429] = 0; - out_7523521905118560137[430] = 0; - out_7523521905118560137[431] = 0; - out_7523521905118560137[432] = 0; - out_7523521905118560137[433] = 0; - out_7523521905118560137[434] = 0; - out_7523521905118560137[435] = 0; - out_7523521905118560137[436] = 0; - out_7523521905118560137[437] = 0; - out_7523521905118560137[438] = 0; - out_7523521905118560137[439] = 0; - out_7523521905118560137[440] = 1; +void F_fun(double *state, double dt, double *out_4332092747232242913) { + out_4332092747232242913[0] = 1; + out_4332092747232242913[1] = 0; + out_4332092747232242913[2] = 0; + out_4332092747232242913[3] = 0; + out_4332092747232242913[4] = 0; + out_4332092747232242913[5] = 0; + out_4332092747232242913[6] = dt; + out_4332092747232242913[7] = 0; + out_4332092747232242913[8] = 0; + out_4332092747232242913[9] = 0; + out_4332092747232242913[10] = 0; + out_4332092747232242913[11] = 0; + out_4332092747232242913[12] = 0; + out_4332092747232242913[13] = 0; + out_4332092747232242913[14] = 0; + out_4332092747232242913[15] = 0; + out_4332092747232242913[16] = 0; + out_4332092747232242913[17] = 0; + out_4332092747232242913[18] = 0; + out_4332092747232242913[19] = 0; + out_4332092747232242913[20] = 0; + out_4332092747232242913[21] = 0; + out_4332092747232242913[22] = 1; + out_4332092747232242913[23] = 0; + out_4332092747232242913[24] = 0; + out_4332092747232242913[25] = 0; + out_4332092747232242913[26] = 0; + out_4332092747232242913[27] = 0; + out_4332092747232242913[28] = dt; + out_4332092747232242913[29] = 0; + out_4332092747232242913[30] = 0; + out_4332092747232242913[31] = 0; + out_4332092747232242913[32] = 0; + out_4332092747232242913[33] = 0; + out_4332092747232242913[34] = 0; + out_4332092747232242913[35] = 0; + out_4332092747232242913[36] = 0; + out_4332092747232242913[37] = 0; + out_4332092747232242913[38] = 0; + out_4332092747232242913[39] = 0; + out_4332092747232242913[40] = 0; + out_4332092747232242913[41] = 0; + out_4332092747232242913[42] = 0; + out_4332092747232242913[43] = 0; + out_4332092747232242913[44] = 1; + out_4332092747232242913[45] = 0; + out_4332092747232242913[46] = 0; + out_4332092747232242913[47] = 0; + out_4332092747232242913[48] = 0; + out_4332092747232242913[49] = 0; + out_4332092747232242913[50] = dt; + out_4332092747232242913[51] = 0; + out_4332092747232242913[52] = 0; + out_4332092747232242913[53] = 0; + out_4332092747232242913[54] = 0; + out_4332092747232242913[55] = 0; + out_4332092747232242913[56] = 0; + out_4332092747232242913[57] = 0; + out_4332092747232242913[58] = 0; + out_4332092747232242913[59] = 0; + out_4332092747232242913[60] = 0; + out_4332092747232242913[61] = 0; + out_4332092747232242913[62] = 0; + out_4332092747232242913[63] = 0; + out_4332092747232242913[64] = 0; + out_4332092747232242913[65] = 0; + out_4332092747232242913[66] = 1; + out_4332092747232242913[67] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[11] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_4332092747232242913[68] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[12] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[10] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[11]); + out_4332092747232242913[69] = 0; + out_4332092747232242913[70] = 0; + out_4332092747232242913[71] = 0; + out_4332092747232242913[72] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_4332092747232242913[73] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_4332092747232242913[74] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_4332092747232242913[75] = 0; + out_4332092747232242913[76] = 0; + out_4332092747232242913[77] = 0; + out_4332092747232242913[78] = 0; + out_4332092747232242913[79] = 0; + out_4332092747232242913[80] = 0; + out_4332092747232242913[81] = 0; + out_4332092747232242913[82] = 0; + out_4332092747232242913[83] = 0; + out_4332092747232242913[84] = 0; + out_4332092747232242913[85] = 0; + out_4332092747232242913[86] = 0; + out_4332092747232242913[87] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[11] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_4332092747232242913[88] = 1; + out_4332092747232242913[89] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[12] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[11] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[10]); + out_4332092747232242913[90] = 0; + out_4332092747232242913[91] = 0; + out_4332092747232242913[92] = 0; + out_4332092747232242913[93] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_4332092747232242913[94] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_4332092747232242913[95] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_4332092747232242913[96] = 0; + out_4332092747232242913[97] = 0; + out_4332092747232242913[98] = 0; + out_4332092747232242913[99] = 0; + out_4332092747232242913[100] = 0; + out_4332092747232242913[101] = 0; + out_4332092747232242913[102] = 0; + out_4332092747232242913[103] = 0; + out_4332092747232242913[104] = 0; + out_4332092747232242913[105] = 0; + out_4332092747232242913[106] = 0; + out_4332092747232242913[107] = 0; + out_4332092747232242913[108] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[12] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[10] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[11]); + out_4332092747232242913[109] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[12] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[11] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[10]); + out_4332092747232242913[110] = 1; + out_4332092747232242913[111] = 0; + out_4332092747232242913[112] = 0; + out_4332092747232242913[113] = 0; + out_4332092747232242913[114] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_4332092747232242913[115] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_4332092747232242913[116] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_4332092747232242913[117] = 0; + out_4332092747232242913[118] = 0; + out_4332092747232242913[119] = 0; + out_4332092747232242913[120] = 0; + out_4332092747232242913[121] = 0; + out_4332092747232242913[122] = 0; + out_4332092747232242913[123] = 0; + out_4332092747232242913[124] = 0; + out_4332092747232242913[125] = 0; + out_4332092747232242913[126] = 0; + out_4332092747232242913[127] = 0; + out_4332092747232242913[128] = 0; + out_4332092747232242913[129] = 0; + out_4332092747232242913[130] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_4332092747232242913[131] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[18] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[16] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[17]); + out_4332092747232242913[132] = 1; + out_4332092747232242913[133] = 0; + out_4332092747232242913[134] = 0; + out_4332092747232242913[135] = 0; + out_4332092747232242913[136] = 0; + out_4332092747232242913[137] = 0; + out_4332092747232242913[138] = 0; + out_4332092747232242913[139] = 0; + out_4332092747232242913[140] = 0; + out_4332092747232242913[141] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_4332092747232242913[142] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_4332092747232242913[143] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_4332092747232242913[144] = 0; + out_4332092747232242913[145] = 0; + out_4332092747232242913[146] = 0; + out_4332092747232242913[147] = 0; + out_4332092747232242913[148] = 0; + out_4332092747232242913[149] = 0; + out_4332092747232242913[150] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[17] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_4332092747232242913[151] = 0; + out_4332092747232242913[152] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]); + out_4332092747232242913[153] = 0; + out_4332092747232242913[154] = 1; + out_4332092747232242913[155] = 0; + out_4332092747232242913[156] = 0; + out_4332092747232242913[157] = 0; + out_4332092747232242913[158] = 0; + out_4332092747232242913[159] = 0; + out_4332092747232242913[160] = 0; + out_4332092747232242913[161] = 0; + out_4332092747232242913[162] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_4332092747232242913[163] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_4332092747232242913[164] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_4332092747232242913[165] = 0; + out_4332092747232242913[166] = 0; + out_4332092747232242913[167] = 0; + out_4332092747232242913[168] = 0; + out_4332092747232242913[169] = 0; + out_4332092747232242913[170] = 0; + out_4332092747232242913[171] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]); + out_4332092747232242913[172] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[18] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[17] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[16]); + out_4332092747232242913[173] = 0; + out_4332092747232242913[174] = 0; + out_4332092747232242913[175] = 0; + out_4332092747232242913[176] = 1; + out_4332092747232242913[177] = 0; + out_4332092747232242913[178] = 0; + out_4332092747232242913[179] = 0; + out_4332092747232242913[180] = 0; + out_4332092747232242913[181] = 0; + out_4332092747232242913[182] = 0; + out_4332092747232242913[183] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_4332092747232242913[184] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_4332092747232242913[185] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_4332092747232242913[186] = 0; + out_4332092747232242913[187] = 0; + out_4332092747232242913[188] = 0; + out_4332092747232242913[189] = 0; + out_4332092747232242913[190] = 0; + out_4332092747232242913[191] = 0; + out_4332092747232242913[192] = 0; + out_4332092747232242913[193] = 0; + out_4332092747232242913[194] = 0; + out_4332092747232242913[195] = 0; + out_4332092747232242913[196] = 0; + out_4332092747232242913[197] = 0; + out_4332092747232242913[198] = 1; + out_4332092747232242913[199] = 0; + out_4332092747232242913[200] = 0; + out_4332092747232242913[201] = 0; + out_4332092747232242913[202] = 0; + out_4332092747232242913[203] = 0; + out_4332092747232242913[204] = 0; + out_4332092747232242913[205] = 0; + out_4332092747232242913[206] = 0; + out_4332092747232242913[207] = 0; + out_4332092747232242913[208] = 0; + out_4332092747232242913[209] = 0; + out_4332092747232242913[210] = 0; + out_4332092747232242913[211] = 0; + out_4332092747232242913[212] = 0; + out_4332092747232242913[213] = 0; + out_4332092747232242913[214] = 0; + out_4332092747232242913[215] = 0; + out_4332092747232242913[216] = 0; + out_4332092747232242913[217] = 0; + out_4332092747232242913[218] = 0; + out_4332092747232242913[219] = 0; + out_4332092747232242913[220] = 1; + out_4332092747232242913[221] = 0; + out_4332092747232242913[222] = 0; + out_4332092747232242913[223] = 0; + out_4332092747232242913[224] = 0; + out_4332092747232242913[225] = 0; + out_4332092747232242913[226] = 0; + out_4332092747232242913[227] = 0; + out_4332092747232242913[228] = 0; + out_4332092747232242913[229] = 0; + out_4332092747232242913[230] = 0; + out_4332092747232242913[231] = 0; + out_4332092747232242913[232] = 0; + out_4332092747232242913[233] = 0; + out_4332092747232242913[234] = 0; + out_4332092747232242913[235] = 0; + out_4332092747232242913[236] = 0; + out_4332092747232242913[237] = 0; + out_4332092747232242913[238] = 0; + out_4332092747232242913[239] = 0; + out_4332092747232242913[240] = 0; + out_4332092747232242913[241] = 0; + out_4332092747232242913[242] = 1; + out_4332092747232242913[243] = 0; + out_4332092747232242913[244] = 0; + out_4332092747232242913[245] = 0; + out_4332092747232242913[246] = 0; + out_4332092747232242913[247] = 0; + out_4332092747232242913[248] = 0; + out_4332092747232242913[249] = 0; + out_4332092747232242913[250] = 0; + out_4332092747232242913[251] = 0; + out_4332092747232242913[252] = 0; + out_4332092747232242913[253] = 0; + out_4332092747232242913[254] = 0; + out_4332092747232242913[255] = 0; + out_4332092747232242913[256] = 0; + out_4332092747232242913[257] = 0; + out_4332092747232242913[258] = 0; + out_4332092747232242913[259] = 0; + out_4332092747232242913[260] = 0; + out_4332092747232242913[261] = 0; + out_4332092747232242913[262] = 0; + out_4332092747232242913[263] = 0; + out_4332092747232242913[264] = 1; + out_4332092747232242913[265] = 0; + out_4332092747232242913[266] = 0; + out_4332092747232242913[267] = 0; + out_4332092747232242913[268] = 0; + out_4332092747232242913[269] = 0; + out_4332092747232242913[270] = 0; + out_4332092747232242913[271] = 0; + out_4332092747232242913[272] = 0; + out_4332092747232242913[273] = 0; + out_4332092747232242913[274] = 0; + out_4332092747232242913[275] = 0; + out_4332092747232242913[276] = 0; + out_4332092747232242913[277] = 0; + out_4332092747232242913[278] = 0; + out_4332092747232242913[279] = 0; + out_4332092747232242913[280] = 0; + out_4332092747232242913[281] = 0; + out_4332092747232242913[282] = 0; + out_4332092747232242913[283] = 0; + out_4332092747232242913[284] = 0; + out_4332092747232242913[285] = 0; + out_4332092747232242913[286] = 1; + out_4332092747232242913[287] = 0; + out_4332092747232242913[288] = 0; + out_4332092747232242913[289] = 0; + out_4332092747232242913[290] = 0; + out_4332092747232242913[291] = 0; + out_4332092747232242913[292] = 0; + out_4332092747232242913[293] = 0; + out_4332092747232242913[294] = 0; + out_4332092747232242913[295] = 0; + out_4332092747232242913[296] = 0; + out_4332092747232242913[297] = 0; + out_4332092747232242913[298] = 0; + out_4332092747232242913[299] = 0; + out_4332092747232242913[300] = 0; + out_4332092747232242913[301] = 0; + out_4332092747232242913[302] = 0; + out_4332092747232242913[303] = 0; + out_4332092747232242913[304] = 0; + out_4332092747232242913[305] = 0; + out_4332092747232242913[306] = 0; + out_4332092747232242913[307] = 0; + out_4332092747232242913[308] = 1; + out_4332092747232242913[309] = 0; + out_4332092747232242913[310] = 0; + out_4332092747232242913[311] = 0; + out_4332092747232242913[312] = 0; + out_4332092747232242913[313] = 0; + out_4332092747232242913[314] = 0; + out_4332092747232242913[315] = 0; + out_4332092747232242913[316] = 0; + out_4332092747232242913[317] = 0; + out_4332092747232242913[318] = 0; + out_4332092747232242913[319] = 0; + out_4332092747232242913[320] = 0; + out_4332092747232242913[321] = 0; + out_4332092747232242913[322] = 0; + out_4332092747232242913[323] = 0; + out_4332092747232242913[324] = 0; + out_4332092747232242913[325] = 0; + out_4332092747232242913[326] = 0; + out_4332092747232242913[327] = 0; + out_4332092747232242913[328] = 0; + out_4332092747232242913[329] = 0; + out_4332092747232242913[330] = 1; + out_4332092747232242913[331] = 0; + out_4332092747232242913[332] = 0; + out_4332092747232242913[333] = 0; + out_4332092747232242913[334] = 0; + out_4332092747232242913[335] = 0; + out_4332092747232242913[336] = 0; + out_4332092747232242913[337] = 0; + out_4332092747232242913[338] = 0; + out_4332092747232242913[339] = 0; + out_4332092747232242913[340] = 0; + out_4332092747232242913[341] = 0; + out_4332092747232242913[342] = 0; + out_4332092747232242913[343] = 0; + out_4332092747232242913[344] = 0; + out_4332092747232242913[345] = 0; + out_4332092747232242913[346] = 0; + out_4332092747232242913[347] = 0; + out_4332092747232242913[348] = 0; + out_4332092747232242913[349] = 0; + out_4332092747232242913[350] = 0; + out_4332092747232242913[351] = 0; + out_4332092747232242913[352] = 1; + out_4332092747232242913[353] = 0; + out_4332092747232242913[354] = 0; + out_4332092747232242913[355] = 0; + out_4332092747232242913[356] = 0; + out_4332092747232242913[357] = 0; + out_4332092747232242913[358] = 0; + out_4332092747232242913[359] = 0; + out_4332092747232242913[360] = 0; + out_4332092747232242913[361] = 0; + out_4332092747232242913[362] = 0; + out_4332092747232242913[363] = 0; + out_4332092747232242913[364] = 0; + out_4332092747232242913[365] = 0; + out_4332092747232242913[366] = 0; + out_4332092747232242913[367] = 0; + out_4332092747232242913[368] = 0; + out_4332092747232242913[369] = 0; + out_4332092747232242913[370] = 0; + out_4332092747232242913[371] = 0; + out_4332092747232242913[372] = 0; + out_4332092747232242913[373] = 0; + out_4332092747232242913[374] = 1; + out_4332092747232242913[375] = 0; + out_4332092747232242913[376] = 0; + out_4332092747232242913[377] = 0; + out_4332092747232242913[378] = 0; + out_4332092747232242913[379] = 0; + out_4332092747232242913[380] = 0; + out_4332092747232242913[381] = 0; + out_4332092747232242913[382] = 0; + out_4332092747232242913[383] = 0; + out_4332092747232242913[384] = 0; + out_4332092747232242913[385] = 0; + out_4332092747232242913[386] = 0; + out_4332092747232242913[387] = 0; + out_4332092747232242913[388] = 0; + out_4332092747232242913[389] = 0; + out_4332092747232242913[390] = 0; + out_4332092747232242913[391] = 0; + out_4332092747232242913[392] = 0; + out_4332092747232242913[393] = 0; + out_4332092747232242913[394] = 0; + out_4332092747232242913[395] = 0; + out_4332092747232242913[396] = 1; + out_4332092747232242913[397] = 0; + out_4332092747232242913[398] = 0; + out_4332092747232242913[399] = 0; + out_4332092747232242913[400] = 0; + out_4332092747232242913[401] = 0; + out_4332092747232242913[402] = 0; + out_4332092747232242913[403] = 0; + out_4332092747232242913[404] = 0; + out_4332092747232242913[405] = 0; + out_4332092747232242913[406] = 0; + out_4332092747232242913[407] = 0; + out_4332092747232242913[408] = 0; + out_4332092747232242913[409] = 0; + out_4332092747232242913[410] = 0; + out_4332092747232242913[411] = 0; + out_4332092747232242913[412] = 0; + out_4332092747232242913[413] = 0; + out_4332092747232242913[414] = 0; + out_4332092747232242913[415] = 0; + out_4332092747232242913[416] = 0; + out_4332092747232242913[417] = 0; + out_4332092747232242913[418] = 1; + out_4332092747232242913[419] = 0; + out_4332092747232242913[420] = 0; + out_4332092747232242913[421] = 0; + out_4332092747232242913[422] = 0; + out_4332092747232242913[423] = 0; + out_4332092747232242913[424] = 0; + out_4332092747232242913[425] = 0; + out_4332092747232242913[426] = 0; + out_4332092747232242913[427] = 0; + out_4332092747232242913[428] = 0; + out_4332092747232242913[429] = 0; + out_4332092747232242913[430] = 0; + out_4332092747232242913[431] = 0; + out_4332092747232242913[432] = 0; + out_4332092747232242913[433] = 0; + out_4332092747232242913[434] = 0; + out_4332092747232242913[435] = 0; + out_4332092747232242913[436] = 0; + out_4332092747232242913[437] = 0; + out_4332092747232242913[438] = 0; + out_4332092747232242913[439] = 0; + out_4332092747232242913[440] = 1; } -void h_4(double *state, double *unused, double *out_874158167075593511) { - out_874158167075593511[0] = state[10] + state[13]; - out_874158167075593511[1] = state[11] + state[14]; - out_874158167075593511[2] = state[12] + state[15]; +void h_4(double *state, double *unused, double *out_6582152946104087701) { + out_6582152946104087701[0] = state[10] + state[13]; + out_6582152946104087701[1] = state[11] + state[14]; + out_6582152946104087701[2] = state[12] + state[15]; } -void H_4(double *state, double *unused, double *out_2890470532950944797) { - out_2890470532950944797[0] = 0; - out_2890470532950944797[1] = 0; - out_2890470532950944797[2] = 0; - out_2890470532950944797[3] = 0; - out_2890470532950944797[4] = 0; - out_2890470532950944797[5] = 0; - out_2890470532950944797[6] = 0; - out_2890470532950944797[7] = 0; - out_2890470532950944797[8] = 0; - out_2890470532950944797[9] = 0; - out_2890470532950944797[10] = 1; - out_2890470532950944797[11] = 0; - out_2890470532950944797[12] = 0; - out_2890470532950944797[13] = 1; - out_2890470532950944797[14] = 0; - out_2890470532950944797[15] = 0; - out_2890470532950944797[16] = 0; - out_2890470532950944797[17] = 0; - out_2890470532950944797[18] = 0; - out_2890470532950944797[19] = 0; - out_2890470532950944797[20] = 0; - out_2890470532950944797[21] = 0; - out_2890470532950944797[22] = 0; - out_2890470532950944797[23] = 0; - out_2890470532950944797[24] = 0; - out_2890470532950944797[25] = 0; - out_2890470532950944797[26] = 0; - out_2890470532950944797[27] = 0; - out_2890470532950944797[28] = 0; - out_2890470532950944797[29] = 0; - out_2890470532950944797[30] = 0; - out_2890470532950944797[31] = 0; - out_2890470532950944797[32] = 0; - out_2890470532950944797[33] = 1; - out_2890470532950944797[34] = 0; - out_2890470532950944797[35] = 0; - out_2890470532950944797[36] = 1; - out_2890470532950944797[37] = 0; - out_2890470532950944797[38] = 0; - out_2890470532950944797[39] = 0; - out_2890470532950944797[40] = 0; - out_2890470532950944797[41] = 0; - out_2890470532950944797[42] = 0; - out_2890470532950944797[43] = 0; - out_2890470532950944797[44] = 0; - out_2890470532950944797[45] = 0; - out_2890470532950944797[46] = 0; - out_2890470532950944797[47] = 0; - out_2890470532950944797[48] = 0; - out_2890470532950944797[49] = 0; - out_2890470532950944797[50] = 0; - out_2890470532950944797[51] = 0; - out_2890470532950944797[52] = 0; - out_2890470532950944797[53] = 0; - out_2890470532950944797[54] = 0; - out_2890470532950944797[55] = 0; - out_2890470532950944797[56] = 1; - out_2890470532950944797[57] = 0; - out_2890470532950944797[58] = 0; - out_2890470532950944797[59] = 1; - out_2890470532950944797[60] = 0; - out_2890470532950944797[61] = 0; - out_2890470532950944797[62] = 0; - out_2890470532950944797[63] = 0; - out_2890470532950944797[64] = 0; - out_2890470532950944797[65] = 0; +void H_4(double *state, double *unused, double *out_8426954437225368770) { + out_8426954437225368770[0] = 0; + out_8426954437225368770[1] = 0; + out_8426954437225368770[2] = 0; + out_8426954437225368770[3] = 0; + out_8426954437225368770[4] = 0; + out_8426954437225368770[5] = 0; + out_8426954437225368770[6] = 0; + out_8426954437225368770[7] = 0; + out_8426954437225368770[8] = 0; + out_8426954437225368770[9] = 0; + out_8426954437225368770[10] = 1; + out_8426954437225368770[11] = 0; + out_8426954437225368770[12] = 0; + out_8426954437225368770[13] = 1; + out_8426954437225368770[14] = 0; + out_8426954437225368770[15] = 0; + out_8426954437225368770[16] = 0; + out_8426954437225368770[17] = 0; + out_8426954437225368770[18] = 0; + out_8426954437225368770[19] = 0; + out_8426954437225368770[20] = 0; + out_8426954437225368770[21] = 0; + out_8426954437225368770[22] = 0; + out_8426954437225368770[23] = 0; + out_8426954437225368770[24] = 0; + out_8426954437225368770[25] = 0; + out_8426954437225368770[26] = 0; + out_8426954437225368770[27] = 0; + out_8426954437225368770[28] = 0; + out_8426954437225368770[29] = 0; + out_8426954437225368770[30] = 0; + out_8426954437225368770[31] = 0; + out_8426954437225368770[32] = 0; + out_8426954437225368770[33] = 1; + out_8426954437225368770[34] = 0; + out_8426954437225368770[35] = 0; + out_8426954437225368770[36] = 1; + out_8426954437225368770[37] = 0; + out_8426954437225368770[38] = 0; + out_8426954437225368770[39] = 0; + out_8426954437225368770[40] = 0; + out_8426954437225368770[41] = 0; + out_8426954437225368770[42] = 0; + out_8426954437225368770[43] = 0; + out_8426954437225368770[44] = 0; + out_8426954437225368770[45] = 0; + out_8426954437225368770[46] = 0; + out_8426954437225368770[47] = 0; + out_8426954437225368770[48] = 0; + out_8426954437225368770[49] = 0; + out_8426954437225368770[50] = 0; + out_8426954437225368770[51] = 0; + out_8426954437225368770[52] = 0; + out_8426954437225368770[53] = 0; + out_8426954437225368770[54] = 0; + out_8426954437225368770[55] = 0; + out_8426954437225368770[56] = 1; + out_8426954437225368770[57] = 0; + out_8426954437225368770[58] = 0; + out_8426954437225368770[59] = 1; + out_8426954437225368770[60] = 0; + out_8426954437225368770[61] = 0; + out_8426954437225368770[62] = 0; + out_8426954437225368770[63] = 0; + out_8426954437225368770[64] = 0; + out_8426954437225368770[65] = 0; } -void h_9(double *state, double *unused, double *out_7169843762143865122) { - out_7169843762143865122[0] = state[10]; - out_7169843762143865122[1] = state[11]; - out_7169843762143865122[2] = state[12]; +void h_9(double *state, double *unused, double *out_7444569565063482614) { + out_7444569565063482614[0] = state[10]; + out_7444569565063482614[1] = state[11]; + out_7444569565063482614[2] = state[12]; } -void H_9(double *state, double *unused, double *out_5779332085231024139) { - out_5779332085231024139[0] = 0; - out_5779332085231024139[1] = 0; - out_5779332085231024139[2] = 0; - out_5779332085231024139[3] = 0; - out_5779332085231024139[4] = 0; - out_5779332085231024139[5] = 0; - out_5779332085231024139[6] = 0; - out_5779332085231024139[7] = 0; - out_5779332085231024139[8] = 0; - out_5779332085231024139[9] = 0; - out_5779332085231024139[10] = 1; - out_5779332085231024139[11] = 0; - out_5779332085231024139[12] = 0; - out_5779332085231024139[13] = 0; - out_5779332085231024139[14] = 0; - out_5779332085231024139[15] = 0; - out_5779332085231024139[16] = 0; - out_5779332085231024139[17] = 0; - out_5779332085231024139[18] = 0; - out_5779332085231024139[19] = 0; - out_5779332085231024139[20] = 0; - out_5779332085231024139[21] = 0; - out_5779332085231024139[22] = 0; - out_5779332085231024139[23] = 0; - out_5779332085231024139[24] = 0; - out_5779332085231024139[25] = 0; - out_5779332085231024139[26] = 0; - out_5779332085231024139[27] = 0; - out_5779332085231024139[28] = 0; - out_5779332085231024139[29] = 0; - out_5779332085231024139[30] = 0; - out_5779332085231024139[31] = 0; - out_5779332085231024139[32] = 0; - out_5779332085231024139[33] = 1; - out_5779332085231024139[34] = 0; - out_5779332085231024139[35] = 0; - out_5779332085231024139[36] = 0; - out_5779332085231024139[37] = 0; - out_5779332085231024139[38] = 0; - out_5779332085231024139[39] = 0; - out_5779332085231024139[40] = 0; - out_5779332085231024139[41] = 0; - out_5779332085231024139[42] = 0; - out_5779332085231024139[43] = 0; - out_5779332085231024139[44] = 0; - out_5779332085231024139[45] = 0; - out_5779332085231024139[46] = 0; - out_5779332085231024139[47] = 0; - out_5779332085231024139[48] = 0; - out_5779332085231024139[49] = 0; - out_5779332085231024139[50] = 0; - out_5779332085231024139[51] = 0; - out_5779332085231024139[52] = 0; - out_5779332085231024139[53] = 0; - out_5779332085231024139[54] = 0; - out_5779332085231024139[55] = 0; - out_5779332085231024139[56] = 1; - out_5779332085231024139[57] = 0; - out_5779332085231024139[58] = 0; - out_5779332085231024139[59] = 0; - out_5779332085231024139[60] = 0; - out_5779332085231024139[61] = 0; - out_5779332085231024139[62] = 0; - out_5779332085231024139[63] = 0; - out_5779332085231024139[64] = 0; - out_5779332085231024139[65] = 0; +void H_9(double *state, double *unused, double *out_7130928084204103504) { + out_7130928084204103504[0] = 0; + out_7130928084204103504[1] = 0; + out_7130928084204103504[2] = 0; + out_7130928084204103504[3] = 0; + out_7130928084204103504[4] = 0; + out_7130928084204103504[5] = 0; + out_7130928084204103504[6] = 0; + out_7130928084204103504[7] = 0; + out_7130928084204103504[8] = 0; + out_7130928084204103504[9] = 0; + out_7130928084204103504[10] = 1; + out_7130928084204103504[11] = 0; + out_7130928084204103504[12] = 0; + out_7130928084204103504[13] = 0; + out_7130928084204103504[14] = 0; + out_7130928084204103504[15] = 0; + out_7130928084204103504[16] = 0; + out_7130928084204103504[17] = 0; + out_7130928084204103504[18] = 0; + out_7130928084204103504[19] = 0; + out_7130928084204103504[20] = 0; + out_7130928084204103504[21] = 0; + out_7130928084204103504[22] = 0; + out_7130928084204103504[23] = 0; + out_7130928084204103504[24] = 0; + out_7130928084204103504[25] = 0; + out_7130928084204103504[26] = 0; + out_7130928084204103504[27] = 0; + out_7130928084204103504[28] = 0; + out_7130928084204103504[29] = 0; + out_7130928084204103504[30] = 0; + out_7130928084204103504[31] = 0; + out_7130928084204103504[32] = 0; + out_7130928084204103504[33] = 1; + out_7130928084204103504[34] = 0; + out_7130928084204103504[35] = 0; + out_7130928084204103504[36] = 0; + out_7130928084204103504[37] = 0; + out_7130928084204103504[38] = 0; + out_7130928084204103504[39] = 0; + out_7130928084204103504[40] = 0; + out_7130928084204103504[41] = 0; + out_7130928084204103504[42] = 0; + out_7130928084204103504[43] = 0; + out_7130928084204103504[44] = 0; + out_7130928084204103504[45] = 0; + out_7130928084204103504[46] = 0; + out_7130928084204103504[47] = 0; + out_7130928084204103504[48] = 0; + out_7130928084204103504[49] = 0; + out_7130928084204103504[50] = 0; + out_7130928084204103504[51] = 0; + out_7130928084204103504[52] = 0; + out_7130928084204103504[53] = 0; + out_7130928084204103504[54] = 0; + out_7130928084204103504[55] = 0; + out_7130928084204103504[56] = 1; + out_7130928084204103504[57] = 0; + out_7130928084204103504[58] = 0; + out_7130928084204103504[59] = 0; + out_7130928084204103504[60] = 0; + out_7130928084204103504[61] = 0; + out_7130928084204103504[62] = 0; + out_7130928084204103504[63] = 0; + out_7130928084204103504[64] = 0; + out_7130928084204103504[65] = 0; } -void h_10(double *state, double *unused, double *out_3163124755553653720) { - out_3163124755553653720[0] = 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0] + state[16] + state[19]; - out_3163124755553653720[1] = 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1] + state[17] + state[20]; - out_3163124755553653720[2] = 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[2] + state[18] + state[21]; +void h_10(double *state, double *unused, double *out_1939752611965379146) { + out_1939752611965379146[0] = 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0] + state[16] + state[19]; + out_1939752611965379146[1] = 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1] + state[17] + state[20]; + out_1939752611965379146[2] = 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[2] + state[18] + state[21]; } -void H_10(double *state, double *unused, double *out_4896893583908803739) { - out_4896893583908803739[0] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*pow(state[0], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_4896893583908803739[1] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; - out_4896893583908803739[2] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[2]; - out_4896893583908803739[3] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_4896893583908803739[4] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_4896893583908803739[5] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_4896893583908803739[6] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_4896893583908803739[7] = 0; - out_4896893583908803739[8] = 0; - out_4896893583908803739[9] = 0; - out_4896893583908803739[10] = 0; - out_4896893583908803739[11] = 0; - out_4896893583908803739[12] = 0; - out_4896893583908803739[13] = 0; - out_4896893583908803739[14] = 0; - out_4896893583908803739[15] = 0; - out_4896893583908803739[16] = 1; - out_4896893583908803739[17] = 0; - out_4896893583908803739[18] = 0; - out_4896893583908803739[19] = 1; - out_4896893583908803739[20] = 0; - out_4896893583908803739[21] = 0; - out_4896893583908803739[22] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; - out_4896893583908803739[23] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*pow(state[1], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_4896893583908803739[24] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1]*state[2]; - out_4896893583908803739[25] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_4896893583908803739[26] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_4896893583908803739[27] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_4896893583908803739[28] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_4896893583908803739[29] = 0; - out_4896893583908803739[30] = 0; - out_4896893583908803739[31] = 0; - out_4896893583908803739[32] = 0; - out_4896893583908803739[33] = 0; - out_4896893583908803739[34] = 0; - out_4896893583908803739[35] = 0; - out_4896893583908803739[36] = 0; - out_4896893583908803739[37] = 0; - out_4896893583908803739[38] = 0; - out_4896893583908803739[39] = 1; - out_4896893583908803739[40] = 0; - out_4896893583908803739[41] = 0; - out_4896893583908803739[42] = 1; - out_4896893583908803739[43] = 0; - out_4896893583908803739[44] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[0]*state[2]; - out_4896893583908803739[45] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[1]*state[2]; - out_4896893583908803739[46] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*pow(state[2], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_4896893583908803739[47] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_4896893583908803739[48] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_4896893583908803739[49] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_4896893583908803739[50] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_4896893583908803739[51] = 0; - out_4896893583908803739[52] = 0; - out_4896893583908803739[53] = 0; - out_4896893583908803739[54] = 0; - out_4896893583908803739[55] = 0; - out_4896893583908803739[56] = 0; - out_4896893583908803739[57] = 0; - out_4896893583908803739[58] = 0; - out_4896893583908803739[59] = 0; - out_4896893583908803739[60] = 0; - out_4896893583908803739[61] = 0; - out_4896893583908803739[62] = 1; - out_4896893583908803739[63] = 0; - out_4896893583908803739[64] = 0; - out_4896893583908803739[65] = 1; +void H_10(double *state, double *unused, double *out_6385265893824183484) { + out_6385265893824183484[0] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*pow(state[0], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_6385265893824183484[1] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_6385265893824183484[2] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[2]; + out_6385265893824183484[3] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_6385265893824183484[4] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_6385265893824183484[5] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_6385265893824183484[6] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_6385265893824183484[7] = 0; + out_6385265893824183484[8] = 0; + out_6385265893824183484[9] = 0; + out_6385265893824183484[10] = 0; + out_6385265893824183484[11] = 0; + out_6385265893824183484[12] = 0; + out_6385265893824183484[13] = 0; + out_6385265893824183484[14] = 0; + out_6385265893824183484[15] = 0; + out_6385265893824183484[16] = 1; + out_6385265893824183484[17] = 0; + out_6385265893824183484[18] = 0; + out_6385265893824183484[19] = 1; + out_6385265893824183484[20] = 0; + out_6385265893824183484[21] = 0; + out_6385265893824183484[22] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_6385265893824183484[23] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*pow(state[1], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_6385265893824183484[24] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1]*state[2]; + out_6385265893824183484[25] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_6385265893824183484[26] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_6385265893824183484[27] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_6385265893824183484[28] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_6385265893824183484[29] = 0; + out_6385265893824183484[30] = 0; + out_6385265893824183484[31] = 0; + out_6385265893824183484[32] = 0; + out_6385265893824183484[33] = 0; + out_6385265893824183484[34] = 0; + out_6385265893824183484[35] = 0; + out_6385265893824183484[36] = 0; + out_6385265893824183484[37] = 0; + out_6385265893824183484[38] = 0; + out_6385265893824183484[39] = 1; + out_6385265893824183484[40] = 0; + out_6385265893824183484[41] = 0; + out_6385265893824183484[42] = 1; + out_6385265893824183484[43] = 0; + out_6385265893824183484[44] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[0]*state[2]; + out_6385265893824183484[45] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[1]*state[2]; + out_6385265893824183484[46] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*pow(state[2], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_6385265893824183484[47] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_6385265893824183484[48] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_6385265893824183484[49] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_6385265893824183484[50] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_6385265893824183484[51] = 0; + out_6385265893824183484[52] = 0; + out_6385265893824183484[53] = 0; + out_6385265893824183484[54] = 0; + out_6385265893824183484[55] = 0; + out_6385265893824183484[56] = 0; + out_6385265893824183484[57] = 0; + out_6385265893824183484[58] = 0; + out_6385265893824183484[59] = 0; + out_6385265893824183484[60] = 0; + out_6385265893824183484[61] = 0; + out_6385265893824183484[62] = 1; + out_6385265893824183484[63] = 0; + out_6385265893824183484[64] = 0; + out_6385265893824183484[65] = 1; } -void h_12(double *state, double *unused, double *out_6187507614461106032) { - out_6187507614461106032[0] = state[0]; - out_6187507614461106032[1] = state[1]; - out_6187507614461106032[2] = state[2]; +void h_12(double *state, double *unused, double *out_7296993372404775801) { + out_7296993372404775801[0] = state[0]; + out_7296993372404775801[1] = state[1]; + out_7296993372404775801[2] = state[2]; } -void H_12(double *state, double *unused, double *out_7889145227076156327) { - out_7889145227076156327[0] = 1; - out_7889145227076156327[1] = 0; - out_7889145227076156327[2] = 0; - out_7889145227076156327[3] = 0; - out_7889145227076156327[4] = 0; - out_7889145227076156327[5] = 0; - out_7889145227076156327[6] = 0; - out_7889145227076156327[7] = 0; - out_7889145227076156327[8] = 0; - out_7889145227076156327[9] = 0; - out_7889145227076156327[10] = 0; - out_7889145227076156327[11] = 0; - out_7889145227076156327[12] = 0; - out_7889145227076156327[13] = 0; - out_7889145227076156327[14] = 0; - out_7889145227076156327[15] = 0; - out_7889145227076156327[16] = 0; - out_7889145227076156327[17] = 0; - out_7889145227076156327[18] = 0; - out_7889145227076156327[19] = 0; - out_7889145227076156327[20] = 0; - out_7889145227076156327[21] = 0; - out_7889145227076156327[22] = 0; - out_7889145227076156327[23] = 1; - out_7889145227076156327[24] = 0; - out_7889145227076156327[25] = 0; - out_7889145227076156327[26] = 0; - out_7889145227076156327[27] = 0; - out_7889145227076156327[28] = 0; - out_7889145227076156327[29] = 0; - out_7889145227076156327[30] = 0; - out_7889145227076156327[31] = 0; - out_7889145227076156327[32] = 0; - out_7889145227076156327[33] = 0; - out_7889145227076156327[34] = 0; - out_7889145227076156327[35] = 0; - out_7889145227076156327[36] = 0; - out_7889145227076156327[37] = 0; - out_7889145227076156327[38] = 0; - out_7889145227076156327[39] = 0; - out_7889145227076156327[40] = 0; - out_7889145227076156327[41] = 0; - out_7889145227076156327[42] = 0; - out_7889145227076156327[43] = 0; - out_7889145227076156327[44] = 0; - out_7889145227076156327[45] = 0; - out_7889145227076156327[46] = 1; - out_7889145227076156327[47] = 0; - out_7889145227076156327[48] = 0; - out_7889145227076156327[49] = 0; - out_7889145227076156327[50] = 0; - out_7889145227076156327[51] = 0; - out_7889145227076156327[52] = 0; - out_7889145227076156327[53] = 0; - out_7889145227076156327[54] = 0; - out_7889145227076156327[55] = 0; - out_7889145227076156327[56] = 0; - out_7889145227076156327[57] = 0; - out_7889145227076156327[58] = 0; - out_7889145227076156327[59] = 0; - out_7889145227076156327[60] = 0; - out_7889145227076156327[61] = 0; - out_7889145227076156327[62] = 0; - out_7889145227076156327[63] = 0; - out_7889145227076156327[64] = 0; - out_7889145227076156327[65] = 0; +void H_12(double *state, double *unused, double *out_2352661322801732354) { + out_2352661322801732354[0] = 1; + out_2352661322801732354[1] = 0; + out_2352661322801732354[2] = 0; + out_2352661322801732354[3] = 0; + out_2352661322801732354[4] = 0; + out_2352661322801732354[5] = 0; + out_2352661322801732354[6] = 0; + out_2352661322801732354[7] = 0; + out_2352661322801732354[8] = 0; + out_2352661322801732354[9] = 0; + out_2352661322801732354[10] = 0; + out_2352661322801732354[11] = 0; + out_2352661322801732354[12] = 0; + out_2352661322801732354[13] = 0; + out_2352661322801732354[14] = 0; + out_2352661322801732354[15] = 0; + out_2352661322801732354[16] = 0; + out_2352661322801732354[17] = 0; + out_2352661322801732354[18] = 0; + out_2352661322801732354[19] = 0; + out_2352661322801732354[20] = 0; + out_2352661322801732354[21] = 0; + out_2352661322801732354[22] = 0; + out_2352661322801732354[23] = 1; + out_2352661322801732354[24] = 0; + out_2352661322801732354[25] = 0; + out_2352661322801732354[26] = 0; + out_2352661322801732354[27] = 0; + out_2352661322801732354[28] = 0; + out_2352661322801732354[29] = 0; + out_2352661322801732354[30] = 0; + out_2352661322801732354[31] = 0; + out_2352661322801732354[32] = 0; + out_2352661322801732354[33] = 0; + out_2352661322801732354[34] = 0; + out_2352661322801732354[35] = 0; + out_2352661322801732354[36] = 0; + out_2352661322801732354[37] = 0; + out_2352661322801732354[38] = 0; + out_2352661322801732354[39] = 0; + out_2352661322801732354[40] = 0; + out_2352661322801732354[41] = 0; + out_2352661322801732354[42] = 0; + out_2352661322801732354[43] = 0; + out_2352661322801732354[44] = 0; + out_2352661322801732354[45] = 0; + out_2352661322801732354[46] = 1; + out_2352661322801732354[47] = 0; + out_2352661322801732354[48] = 0; + out_2352661322801732354[49] = 0; + out_2352661322801732354[50] = 0; + out_2352661322801732354[51] = 0; + out_2352661322801732354[52] = 0; + out_2352661322801732354[53] = 0; + out_2352661322801732354[54] = 0; + out_2352661322801732354[55] = 0; + out_2352661322801732354[56] = 0; + out_2352661322801732354[57] = 0; + out_2352661322801732354[58] = 0; + out_2352661322801732354[59] = 0; + out_2352661322801732354[60] = 0; + out_2352661322801732354[61] = 0; + out_2352661322801732354[62] = 0; + out_2352661322801732354[63] = 0; + out_2352661322801732354[64] = 0; + out_2352661322801732354[65] = 0; } -void h_35(double *state, double *unused, double *out_4266066339955691863) { - out_4266066339955691863[0] = state[7]; - out_4266066339955691863[1] = state[8]; - out_4266066339955691863[2] = state[9]; +void h_35(double *state, double *unused, double *out_947171662528612088) { + out_947171662528612088[0] = state[7]; + out_947171662528612088[1] = state[8]; + out_947171662528612088[2] = state[9]; } -void H_35(double *state, double *unused, double *out_5143582194751142618) { - out_5143582194751142618[0] = 0; - out_5143582194751142618[1] = 0; - out_5143582194751142618[2] = 0; - out_5143582194751142618[3] = 0; - out_5143582194751142618[4] = 0; - out_5143582194751142618[5] = 0; - out_5143582194751142618[6] = 0; - out_5143582194751142618[7] = 1; - out_5143582194751142618[8] = 0; - out_5143582194751142618[9] = 0; - out_5143582194751142618[10] = 0; - out_5143582194751142618[11] = 0; - out_5143582194751142618[12] = 0; - out_5143582194751142618[13] = 0; - out_5143582194751142618[14] = 0; - out_5143582194751142618[15] = 0; - out_5143582194751142618[16] = 0; - out_5143582194751142618[17] = 0; - out_5143582194751142618[18] = 0; - out_5143582194751142618[19] = 0; - out_5143582194751142618[20] = 0; - out_5143582194751142618[21] = 0; - out_5143582194751142618[22] = 0; - out_5143582194751142618[23] = 0; - out_5143582194751142618[24] = 0; - out_5143582194751142618[25] = 0; - out_5143582194751142618[26] = 0; - out_5143582194751142618[27] = 0; - out_5143582194751142618[28] = 0; - out_5143582194751142618[29] = 0; - out_5143582194751142618[30] = 1; - out_5143582194751142618[31] = 0; - out_5143582194751142618[32] = 0; - out_5143582194751142618[33] = 0; - out_5143582194751142618[34] = 0; - out_5143582194751142618[35] = 0; - out_5143582194751142618[36] = 0; - out_5143582194751142618[37] = 0; - out_5143582194751142618[38] = 0; - out_5143582194751142618[39] = 0; - out_5143582194751142618[40] = 0; - out_5143582194751142618[41] = 0; - out_5143582194751142618[42] = 0; - out_5143582194751142618[43] = 0; - out_5143582194751142618[44] = 0; - out_5143582194751142618[45] = 0; - out_5143582194751142618[46] = 0; - out_5143582194751142618[47] = 0; - out_5143582194751142618[48] = 0; - out_5143582194751142618[49] = 0; - out_5143582194751142618[50] = 0; - out_5143582194751142618[51] = 0; - out_5143582194751142618[52] = 0; - out_5143582194751142618[53] = 1; - out_5143582194751142618[54] = 0; - out_5143582194751142618[55] = 0; - out_5143582194751142618[56] = 0; - out_5143582194751142618[57] = 0; - out_5143582194751142618[58] = 0; - out_5143582194751142618[59] = 0; - out_5143582194751142618[60] = 0; - out_5143582194751142618[61] = 0; - out_5143582194751142618[62] = 0; - out_5143582194751142618[63] = 0; - out_5143582194751142618[64] = 0; - out_5143582194751142618[65] = 0; +void H_35(double *state, double *unused, double *out_392901709523281355) { + out_392901709523281355[0] = 0; + out_392901709523281355[1] = 0; + out_392901709523281355[2] = 0; + out_392901709523281355[3] = 0; + out_392901709523281355[4] = 0; + out_392901709523281355[5] = 0; + out_392901709523281355[6] = 0; + out_392901709523281355[7] = 1; + out_392901709523281355[8] = 0; + out_392901709523281355[9] = 0; + out_392901709523281355[10] = 0; + out_392901709523281355[11] = 0; + out_392901709523281355[12] = 0; + out_392901709523281355[13] = 0; + out_392901709523281355[14] = 0; + out_392901709523281355[15] = 0; + out_392901709523281355[16] = 0; + out_392901709523281355[17] = 0; + out_392901709523281355[18] = 0; + out_392901709523281355[19] = 0; + out_392901709523281355[20] = 0; + out_392901709523281355[21] = 0; + out_392901709523281355[22] = 0; + out_392901709523281355[23] = 0; + out_392901709523281355[24] = 0; + out_392901709523281355[25] = 0; + out_392901709523281355[26] = 0; + out_392901709523281355[27] = 0; + out_392901709523281355[28] = 0; + out_392901709523281355[29] = 0; + out_392901709523281355[30] = 1; + out_392901709523281355[31] = 0; + out_392901709523281355[32] = 0; + out_392901709523281355[33] = 0; + out_392901709523281355[34] = 0; + out_392901709523281355[35] = 0; + out_392901709523281355[36] = 0; + out_392901709523281355[37] = 0; + out_392901709523281355[38] = 0; + out_392901709523281355[39] = 0; + out_392901709523281355[40] = 0; + out_392901709523281355[41] = 0; + out_392901709523281355[42] = 0; + out_392901709523281355[43] = 0; + out_392901709523281355[44] = 0; + out_392901709523281355[45] = 0; + out_392901709523281355[46] = 0; + out_392901709523281355[47] = 0; + out_392901709523281355[48] = 0; + out_392901709523281355[49] = 0; + out_392901709523281355[50] = 0; + out_392901709523281355[51] = 0; + out_392901709523281355[52] = 0; + out_392901709523281355[53] = 1; + out_392901709523281355[54] = 0; + out_392901709523281355[55] = 0; + out_392901709523281355[56] = 0; + out_392901709523281355[57] = 0; + out_392901709523281355[58] = 0; + out_392901709523281355[59] = 0; + out_392901709523281355[60] = 0; + out_392901709523281355[61] = 0; + out_392901709523281355[62] = 0; + out_392901709523281355[63] = 0; + out_392901709523281355[64] = 0; + out_392901709523281355[65] = 0; } -void h_32(double *state, double *unused, double *out_9055313354289894635) { - out_9055313354289894635[0] = state[3]; - out_9055313354289894635[1] = state[4]; - out_9055313354289894635[2] = state[5]; - out_9055313354289894635[3] = state[6]; +void h_32(double *state, double *unused, double *out_2929900686975731664) { + out_2929900686975731664[0] = state[3]; + out_2929900686975731664[1] = state[4]; + out_2929900686975731664[2] = state[5]; + out_2929900686975731664[3] = state[6]; } -void H_32(double *state, double *unused, double *out_6388297375264292642) { - out_6388297375264292642[0] = 0; - out_6388297375264292642[1] = 0; - out_6388297375264292642[2] = 0; - out_6388297375264292642[3] = 1; - out_6388297375264292642[4] = 0; - out_6388297375264292642[5] = 0; - out_6388297375264292642[6] = 0; - out_6388297375264292642[7] = 0; - out_6388297375264292642[8] = 0; - out_6388297375264292642[9] = 0; - out_6388297375264292642[10] = 0; - out_6388297375264292642[11] = 0; - out_6388297375264292642[12] = 0; - out_6388297375264292642[13] = 0; - out_6388297375264292642[14] = 0; - out_6388297375264292642[15] = 0; - out_6388297375264292642[16] = 0; - out_6388297375264292642[17] = 0; - out_6388297375264292642[18] = 0; - out_6388297375264292642[19] = 0; - out_6388297375264292642[20] = 0; - out_6388297375264292642[21] = 0; - out_6388297375264292642[22] = 0; - out_6388297375264292642[23] = 0; - out_6388297375264292642[24] = 0; - out_6388297375264292642[25] = 0; - out_6388297375264292642[26] = 1; - out_6388297375264292642[27] = 0; - out_6388297375264292642[28] = 0; - out_6388297375264292642[29] = 0; - out_6388297375264292642[30] = 0; - out_6388297375264292642[31] = 0; - out_6388297375264292642[32] = 0; - out_6388297375264292642[33] = 0; - out_6388297375264292642[34] = 0; - out_6388297375264292642[35] = 0; - out_6388297375264292642[36] = 0; - out_6388297375264292642[37] = 0; - out_6388297375264292642[38] = 0; - out_6388297375264292642[39] = 0; - out_6388297375264292642[40] = 0; - out_6388297375264292642[41] = 0; - out_6388297375264292642[42] = 0; - out_6388297375264292642[43] = 0; - out_6388297375264292642[44] = 0; - out_6388297375264292642[45] = 0; - out_6388297375264292642[46] = 0; - out_6388297375264292642[47] = 0; - out_6388297375264292642[48] = 0; - out_6388297375264292642[49] = 1; - out_6388297375264292642[50] = 0; - out_6388297375264292642[51] = 0; - out_6388297375264292642[52] = 0; - out_6388297375264292642[53] = 0; - out_6388297375264292642[54] = 0; - out_6388297375264292642[55] = 0; - out_6388297375264292642[56] = 0; - out_6388297375264292642[57] = 0; - out_6388297375264292642[58] = 0; - out_6388297375264292642[59] = 0; - out_6388297375264292642[60] = 0; - out_6388297375264292642[61] = 0; - out_6388297375264292642[62] = 0; - out_6388297375264292642[63] = 0; - out_6388297375264292642[64] = 0; - out_6388297375264292642[65] = 0; - out_6388297375264292642[66] = 0; - out_6388297375264292642[67] = 0; - out_6388297375264292642[68] = 0; - out_6388297375264292642[69] = 0; - out_6388297375264292642[70] = 0; - out_6388297375264292642[71] = 0; - out_6388297375264292642[72] = 1; - out_6388297375264292642[73] = 0; - out_6388297375264292642[74] = 0; - out_6388297375264292642[75] = 0; - out_6388297375264292642[76] = 0; - out_6388297375264292642[77] = 0; - out_6388297375264292642[78] = 0; - out_6388297375264292642[79] = 0; - out_6388297375264292642[80] = 0; - out_6388297375264292642[81] = 0; - out_6388297375264292642[82] = 0; - out_6388297375264292642[83] = 0; - out_6388297375264292642[84] = 0; - out_6388297375264292642[85] = 0; - out_6388297375264292642[86] = 0; - out_6388297375264292642[87] = 0; +void H_32(double *state, double *unused, double *out_8907135071749521650) { + out_8907135071749521650[0] = 0; + out_8907135071749521650[1] = 0; + out_8907135071749521650[2] = 0; + out_8907135071749521650[3] = 1; + out_8907135071749521650[4] = 0; + out_8907135071749521650[5] = 0; + out_8907135071749521650[6] = 0; + out_8907135071749521650[7] = 0; + out_8907135071749521650[8] = 0; + out_8907135071749521650[9] = 0; + out_8907135071749521650[10] = 0; + out_8907135071749521650[11] = 0; + out_8907135071749521650[12] = 0; + out_8907135071749521650[13] = 0; + out_8907135071749521650[14] = 0; + out_8907135071749521650[15] = 0; + out_8907135071749521650[16] = 0; + out_8907135071749521650[17] = 0; + out_8907135071749521650[18] = 0; + out_8907135071749521650[19] = 0; + out_8907135071749521650[20] = 0; + out_8907135071749521650[21] = 0; + out_8907135071749521650[22] = 0; + out_8907135071749521650[23] = 0; + out_8907135071749521650[24] = 0; + out_8907135071749521650[25] = 0; + out_8907135071749521650[26] = 1; + out_8907135071749521650[27] = 0; + out_8907135071749521650[28] = 0; + out_8907135071749521650[29] = 0; + out_8907135071749521650[30] = 0; + out_8907135071749521650[31] = 0; + out_8907135071749521650[32] = 0; + out_8907135071749521650[33] = 0; + out_8907135071749521650[34] = 0; + out_8907135071749521650[35] = 0; + out_8907135071749521650[36] = 0; + out_8907135071749521650[37] = 0; + out_8907135071749521650[38] = 0; + out_8907135071749521650[39] = 0; + out_8907135071749521650[40] = 0; + out_8907135071749521650[41] = 0; + out_8907135071749521650[42] = 0; + out_8907135071749521650[43] = 0; + out_8907135071749521650[44] = 0; + out_8907135071749521650[45] = 0; + out_8907135071749521650[46] = 0; + out_8907135071749521650[47] = 0; + out_8907135071749521650[48] = 0; + out_8907135071749521650[49] = 1; + out_8907135071749521650[50] = 0; + out_8907135071749521650[51] = 0; + out_8907135071749521650[52] = 0; + out_8907135071749521650[53] = 0; + out_8907135071749521650[54] = 0; + out_8907135071749521650[55] = 0; + out_8907135071749521650[56] = 0; + out_8907135071749521650[57] = 0; + out_8907135071749521650[58] = 0; + out_8907135071749521650[59] = 0; + out_8907135071749521650[60] = 0; + out_8907135071749521650[61] = 0; + out_8907135071749521650[62] = 0; + out_8907135071749521650[63] = 0; + out_8907135071749521650[64] = 0; + out_8907135071749521650[65] = 0; + out_8907135071749521650[66] = 0; + out_8907135071749521650[67] = 0; + out_8907135071749521650[68] = 0; + out_8907135071749521650[69] = 0; + out_8907135071749521650[70] = 0; + out_8907135071749521650[71] = 0; + out_8907135071749521650[72] = 1; + out_8907135071749521650[73] = 0; + out_8907135071749521650[74] = 0; + out_8907135071749521650[75] = 0; + out_8907135071749521650[76] = 0; + out_8907135071749521650[77] = 0; + out_8907135071749521650[78] = 0; + out_8907135071749521650[79] = 0; + out_8907135071749521650[80] = 0; + out_8907135071749521650[81] = 0; + out_8907135071749521650[82] = 0; + out_8907135071749521650[83] = 0; + out_8907135071749521650[84] = 0; + out_8907135071749521650[85] = 0; + out_8907135071749521650[86] = 0; + out_8907135071749521650[87] = 0; } -void h_13(double *state, double *unused, double *out_7078564321862276630) { - out_7078564321862276630[0] = (-2*state[3]*state[5] + 2*state[4]*state[6])*state[9] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[8] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[7]; - out_7078564321862276630[1] = (2*state[3]*state[4] + 2*state[5]*state[6])*state[9] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[7] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[8]; - out_7078564321862276630[2] = (-2*state[3]*state[4] + 2*state[5]*state[6])*state[8] + (2*state[3]*state[5] + 2*state[4]*state[6])*state[7] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[9]; +void h_13(double *state, double *unused, double *out_4581312559012542837) { + out_4581312559012542837[0] = (-2*state[3]*state[5] + 2*state[4]*state[6])*state[9] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[8] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[7]; + out_4581312559012542837[1] = (2*state[3]*state[4] + 2*state[5]*state[6])*state[9] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[7] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[8]; + out_4581312559012542837[2] = (-2*state[3]*state[4] + 2*state[5]*state[6])*state[8] + (2*state[3]*state[5] + 2*state[4]*state[6])*state[7] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[9]; } -void H_13(double *state, double *unused, double *out_7646665591930494052) { - out_7646665591930494052[0] = 0; - out_7646665591930494052[1] = 0; - out_7646665591930494052[2] = 0; - out_7646665591930494052[3] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; - out_7646665591930494052[4] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7646665591930494052[5] = -2*state[3]*state[9] + 2*state[4]*state[8] - 2*state[5]*state[7]; - out_7646665591930494052[6] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; - out_7646665591930494052[7] = pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2); - out_7646665591930494052[8] = 2*state[3]*state[6] + 2*state[4]*state[5]; - out_7646665591930494052[9] = -2*state[3]*state[5] + 2*state[4]*state[6]; - out_7646665591930494052[10] = 0; - out_7646665591930494052[11] = 0; - out_7646665591930494052[12] = 0; - out_7646665591930494052[13] = 0; - out_7646665591930494052[14] = 0; - out_7646665591930494052[15] = 0; - out_7646665591930494052[16] = 0; - out_7646665591930494052[17] = 0; - out_7646665591930494052[18] = 0; - out_7646665591930494052[19] = 0; - out_7646665591930494052[20] = 0; - out_7646665591930494052[21] = 0; - out_7646665591930494052[22] = 0; - out_7646665591930494052[23] = 0; - out_7646665591930494052[24] = 0; - out_7646665591930494052[25] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; - out_7646665591930494052[26] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; - out_7646665591930494052[27] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7646665591930494052[28] = -2*state[3]*state[7] + 2*state[5]*state[9] - 2*state[6]*state[8]; - out_7646665591930494052[29] = -2*state[3]*state[6] + 2*state[4]*state[5]; - out_7646665591930494052[30] = pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2); - out_7646665591930494052[31] = 2*state[3]*state[4] + 2*state[5]*state[6]; - out_7646665591930494052[32] = 0; - out_7646665591930494052[33] = 0; - out_7646665591930494052[34] = 0; - out_7646665591930494052[35] = 0; - out_7646665591930494052[36] = 0; - out_7646665591930494052[37] = 0; - out_7646665591930494052[38] = 0; - out_7646665591930494052[39] = 0; - out_7646665591930494052[40] = 0; - out_7646665591930494052[41] = 0; - out_7646665591930494052[42] = 0; - out_7646665591930494052[43] = 0; - out_7646665591930494052[44] = 0; - out_7646665591930494052[45] = 0; - out_7646665591930494052[46] = 0; - out_7646665591930494052[47] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; - out_7646665591930494052[48] = -2*state[3]*state[8] - 2*state[4]*state[9] + 2*state[6]*state[7]; - out_7646665591930494052[49] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; - out_7646665591930494052[50] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7646665591930494052[51] = 2*state[3]*state[5] + 2*state[4]*state[6]; - out_7646665591930494052[52] = -2*state[3]*state[4] + 2*state[5]*state[6]; - out_7646665591930494052[53] = pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2); - out_7646665591930494052[54] = 0; - out_7646665591930494052[55] = 0; - out_7646665591930494052[56] = 0; - out_7646665591930494052[57] = 0; - out_7646665591930494052[58] = 0; - out_7646665591930494052[59] = 0; - out_7646665591930494052[60] = 0; - out_7646665591930494052[61] = 0; - out_7646665591930494052[62] = 0; - out_7646665591930494052[63] = 0; - out_7646665591930494052[64] = 0; - out_7646665591930494052[65] = 0; +void H_13(double *state, double *unused, double *out_569470278268388809) { + out_569470278268388809[0] = 0; + out_569470278268388809[1] = 0; + out_569470278268388809[2] = 0; + out_569470278268388809[3] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_569470278268388809[4] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_569470278268388809[5] = -2*state[3]*state[9] + 2*state[4]*state[8] - 2*state[5]*state[7]; + out_569470278268388809[6] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_569470278268388809[7] = pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2); + out_569470278268388809[8] = 2*state[3]*state[6] + 2*state[4]*state[5]; + out_569470278268388809[9] = -2*state[3]*state[5] + 2*state[4]*state[6]; + out_569470278268388809[10] = 0; + out_569470278268388809[11] = 0; + out_569470278268388809[12] = 0; + out_569470278268388809[13] = 0; + out_569470278268388809[14] = 0; + out_569470278268388809[15] = 0; + out_569470278268388809[16] = 0; + out_569470278268388809[17] = 0; + out_569470278268388809[18] = 0; + out_569470278268388809[19] = 0; + out_569470278268388809[20] = 0; + out_569470278268388809[21] = 0; + out_569470278268388809[22] = 0; + out_569470278268388809[23] = 0; + out_569470278268388809[24] = 0; + out_569470278268388809[25] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_569470278268388809[26] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_569470278268388809[27] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_569470278268388809[28] = -2*state[3]*state[7] + 2*state[5]*state[9] - 2*state[6]*state[8]; + out_569470278268388809[29] = -2*state[3]*state[6] + 2*state[4]*state[5]; + out_569470278268388809[30] = pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2); + out_569470278268388809[31] = 2*state[3]*state[4] + 2*state[5]*state[6]; + out_569470278268388809[32] = 0; + out_569470278268388809[33] = 0; + out_569470278268388809[34] = 0; + out_569470278268388809[35] = 0; + out_569470278268388809[36] = 0; + out_569470278268388809[37] = 0; + out_569470278268388809[38] = 0; + out_569470278268388809[39] = 0; + out_569470278268388809[40] = 0; + out_569470278268388809[41] = 0; + out_569470278268388809[42] = 0; + out_569470278268388809[43] = 0; + out_569470278268388809[44] = 0; + out_569470278268388809[45] = 0; + out_569470278268388809[46] = 0; + out_569470278268388809[47] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_569470278268388809[48] = -2*state[3]*state[8] - 2*state[4]*state[9] + 2*state[6]*state[7]; + out_569470278268388809[49] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_569470278268388809[50] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_569470278268388809[51] = 2*state[3]*state[5] + 2*state[4]*state[6]; + out_569470278268388809[52] = -2*state[3]*state[4] + 2*state[5]*state[6]; + out_569470278268388809[53] = pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2); + out_569470278268388809[54] = 0; + out_569470278268388809[55] = 0; + out_569470278268388809[56] = 0; + out_569470278268388809[57] = 0; + out_569470278268388809[58] = 0; + out_569470278268388809[59] = 0; + out_569470278268388809[60] = 0; + out_569470278268388809[61] = 0; + out_569470278268388809[62] = 0; + out_569470278268388809[63] = 0; + out_569470278268388809[64] = 0; + out_569470278268388809[65] = 0; } -void h_14(double *state, double *unused, double *out_7169843762143865122) { - out_7169843762143865122[0] = state[10]; - out_7169843762143865122[1] = state[11]; - out_7169843762143865122[2] = state[12]; +void h_14(double *state, double *unused, double *out_7444569565063482614) { + out_7444569565063482614[0] = state[10]; + out_7444569565063482614[1] = state[11]; + out_7444569565063482614[2] = state[12]; } -void H_14(double *state, double *unused, double *out_5779332085231024139) { - out_5779332085231024139[0] = 0; - out_5779332085231024139[1] = 0; - out_5779332085231024139[2] = 0; - out_5779332085231024139[3] = 0; - out_5779332085231024139[4] = 0; - out_5779332085231024139[5] = 0; - out_5779332085231024139[6] = 0; - out_5779332085231024139[7] = 0; - out_5779332085231024139[8] = 0; - out_5779332085231024139[9] = 0; - out_5779332085231024139[10] = 1; - out_5779332085231024139[11] = 0; - out_5779332085231024139[12] = 0; - out_5779332085231024139[13] = 0; - out_5779332085231024139[14] = 0; - out_5779332085231024139[15] = 0; - out_5779332085231024139[16] = 0; - out_5779332085231024139[17] = 0; - out_5779332085231024139[18] = 0; - out_5779332085231024139[19] = 0; - out_5779332085231024139[20] = 0; - out_5779332085231024139[21] = 0; - out_5779332085231024139[22] = 0; - out_5779332085231024139[23] = 0; - out_5779332085231024139[24] = 0; - out_5779332085231024139[25] = 0; - out_5779332085231024139[26] = 0; - out_5779332085231024139[27] = 0; - out_5779332085231024139[28] = 0; - out_5779332085231024139[29] = 0; - out_5779332085231024139[30] = 0; - out_5779332085231024139[31] = 0; - out_5779332085231024139[32] = 0; - out_5779332085231024139[33] = 1; - out_5779332085231024139[34] = 0; - out_5779332085231024139[35] = 0; - out_5779332085231024139[36] = 0; - out_5779332085231024139[37] = 0; - out_5779332085231024139[38] = 0; - out_5779332085231024139[39] = 0; - out_5779332085231024139[40] = 0; - out_5779332085231024139[41] = 0; - out_5779332085231024139[42] = 0; - out_5779332085231024139[43] = 0; - out_5779332085231024139[44] = 0; - out_5779332085231024139[45] = 0; - out_5779332085231024139[46] = 0; - out_5779332085231024139[47] = 0; - out_5779332085231024139[48] = 0; - out_5779332085231024139[49] = 0; - out_5779332085231024139[50] = 0; - out_5779332085231024139[51] = 0; - out_5779332085231024139[52] = 0; - out_5779332085231024139[53] = 0; - out_5779332085231024139[54] = 0; - out_5779332085231024139[55] = 0; - out_5779332085231024139[56] = 1; - out_5779332085231024139[57] = 0; - out_5779332085231024139[58] = 0; - out_5779332085231024139[59] = 0; - out_5779332085231024139[60] = 0; - out_5779332085231024139[61] = 0; - out_5779332085231024139[62] = 0; - out_5779332085231024139[63] = 0; - out_5779332085231024139[64] = 0; - out_5779332085231024139[65] = 0; +void H_14(double *state, double *unused, double *out_7130928084204103504) { + out_7130928084204103504[0] = 0; + out_7130928084204103504[1] = 0; + out_7130928084204103504[2] = 0; + out_7130928084204103504[3] = 0; + out_7130928084204103504[4] = 0; + out_7130928084204103504[5] = 0; + out_7130928084204103504[6] = 0; + out_7130928084204103504[7] = 0; + out_7130928084204103504[8] = 0; + out_7130928084204103504[9] = 0; + out_7130928084204103504[10] = 1; + out_7130928084204103504[11] = 0; + out_7130928084204103504[12] = 0; + out_7130928084204103504[13] = 0; + out_7130928084204103504[14] = 0; + out_7130928084204103504[15] = 0; + out_7130928084204103504[16] = 0; + out_7130928084204103504[17] = 0; + out_7130928084204103504[18] = 0; + out_7130928084204103504[19] = 0; + out_7130928084204103504[20] = 0; + out_7130928084204103504[21] = 0; + out_7130928084204103504[22] = 0; + out_7130928084204103504[23] = 0; + out_7130928084204103504[24] = 0; + out_7130928084204103504[25] = 0; + out_7130928084204103504[26] = 0; + out_7130928084204103504[27] = 0; + out_7130928084204103504[28] = 0; + out_7130928084204103504[29] = 0; + out_7130928084204103504[30] = 0; + out_7130928084204103504[31] = 0; + out_7130928084204103504[32] = 0; + out_7130928084204103504[33] = 1; + out_7130928084204103504[34] = 0; + out_7130928084204103504[35] = 0; + out_7130928084204103504[36] = 0; + out_7130928084204103504[37] = 0; + out_7130928084204103504[38] = 0; + out_7130928084204103504[39] = 0; + out_7130928084204103504[40] = 0; + out_7130928084204103504[41] = 0; + out_7130928084204103504[42] = 0; + out_7130928084204103504[43] = 0; + out_7130928084204103504[44] = 0; + out_7130928084204103504[45] = 0; + out_7130928084204103504[46] = 0; + out_7130928084204103504[47] = 0; + out_7130928084204103504[48] = 0; + out_7130928084204103504[49] = 0; + out_7130928084204103504[50] = 0; + out_7130928084204103504[51] = 0; + out_7130928084204103504[52] = 0; + out_7130928084204103504[53] = 0; + out_7130928084204103504[54] = 0; + out_7130928084204103504[55] = 0; + out_7130928084204103504[56] = 1; + out_7130928084204103504[57] = 0; + out_7130928084204103504[58] = 0; + out_7130928084204103504[59] = 0; + out_7130928084204103504[60] = 0; + out_7130928084204103504[61] = 0; + out_7130928084204103504[62] = 0; + out_7130928084204103504[63] = 0; + out_7130928084204103504[64] = 0; + out_7130928084204103504[65] = 0; } -void h_33(double *state, double *unused, double *out_3878198370963190653) { - out_3878198370963190653[0] = state[16]; - out_3878198370963190653[1] = state[17]; - out_3878198370963190653[2] = state[18]; +void h_33(double *state, double *unused, double *out_7317084925230058116) { + out_7317084925230058116[0] = state[16]; + out_7317084925230058116[1] = state[17]; + out_7317084925230058116[2] = state[18]; } -void H_33(double *state, double *unused, double *out_1993025190112285014) { - out_1993025190112285014[0] = 0; - out_1993025190112285014[1] = 0; - out_1993025190112285014[2] = 0; - out_1993025190112285014[3] = 0; - out_1993025190112285014[4] = 0; - out_1993025190112285014[5] = 0; - out_1993025190112285014[6] = 0; - out_1993025190112285014[7] = 0; - out_1993025190112285014[8] = 0; - out_1993025190112285014[9] = 0; - out_1993025190112285014[10] = 0; - out_1993025190112285014[11] = 0; - out_1993025190112285014[12] = 0; - out_1993025190112285014[13] = 0; - out_1993025190112285014[14] = 0; - out_1993025190112285014[15] = 0; - out_1993025190112285014[16] = 1; - out_1993025190112285014[17] = 0; - out_1993025190112285014[18] = 0; - out_1993025190112285014[19] = 0; - out_1993025190112285014[20] = 0; - out_1993025190112285014[21] = 0; - out_1993025190112285014[22] = 0; - out_1993025190112285014[23] = 0; - out_1993025190112285014[24] = 0; - out_1993025190112285014[25] = 0; - out_1993025190112285014[26] = 0; - out_1993025190112285014[27] = 0; - out_1993025190112285014[28] = 0; - out_1993025190112285014[29] = 0; - out_1993025190112285014[30] = 0; - out_1993025190112285014[31] = 0; - out_1993025190112285014[32] = 0; - out_1993025190112285014[33] = 0; - out_1993025190112285014[34] = 0; - out_1993025190112285014[35] = 0; - out_1993025190112285014[36] = 0; - out_1993025190112285014[37] = 0; - out_1993025190112285014[38] = 0; - out_1993025190112285014[39] = 1; - out_1993025190112285014[40] = 0; - out_1993025190112285014[41] = 0; - out_1993025190112285014[42] = 0; - out_1993025190112285014[43] = 0; - out_1993025190112285014[44] = 0; - out_1993025190112285014[45] = 0; - out_1993025190112285014[46] = 0; - out_1993025190112285014[47] = 0; - out_1993025190112285014[48] = 0; - out_1993025190112285014[49] = 0; - out_1993025190112285014[50] = 0; - out_1993025190112285014[51] = 0; - out_1993025190112285014[52] = 0; - out_1993025190112285014[53] = 0; - out_1993025190112285014[54] = 0; - out_1993025190112285014[55] = 0; - out_1993025190112285014[56] = 0; - out_1993025190112285014[57] = 0; - out_1993025190112285014[58] = 0; - out_1993025190112285014[59] = 0; - out_1993025190112285014[60] = 0; - out_1993025190112285014[61] = 0; - out_1993025190112285014[62] = 1; - out_1993025190112285014[63] = 0; - out_1993025190112285014[64] = 0; - out_1993025190112285014[65] = 0; +void H_33(double *state, double *unused, double *out_3543458714162138959) { + out_3543458714162138959[0] = 0; + out_3543458714162138959[1] = 0; + out_3543458714162138959[2] = 0; + out_3543458714162138959[3] = 0; + out_3543458714162138959[4] = 0; + out_3543458714162138959[5] = 0; + out_3543458714162138959[6] = 0; + out_3543458714162138959[7] = 0; + out_3543458714162138959[8] = 0; + out_3543458714162138959[9] = 0; + out_3543458714162138959[10] = 0; + out_3543458714162138959[11] = 0; + out_3543458714162138959[12] = 0; + out_3543458714162138959[13] = 0; + out_3543458714162138959[14] = 0; + out_3543458714162138959[15] = 0; + out_3543458714162138959[16] = 1; + out_3543458714162138959[17] = 0; + out_3543458714162138959[18] = 0; + out_3543458714162138959[19] = 0; + out_3543458714162138959[20] = 0; + out_3543458714162138959[21] = 0; + out_3543458714162138959[22] = 0; + out_3543458714162138959[23] = 0; + out_3543458714162138959[24] = 0; + out_3543458714162138959[25] = 0; + out_3543458714162138959[26] = 0; + out_3543458714162138959[27] = 0; + out_3543458714162138959[28] = 0; + out_3543458714162138959[29] = 0; + out_3543458714162138959[30] = 0; + out_3543458714162138959[31] = 0; + out_3543458714162138959[32] = 0; + out_3543458714162138959[33] = 0; + out_3543458714162138959[34] = 0; + out_3543458714162138959[35] = 0; + out_3543458714162138959[36] = 0; + out_3543458714162138959[37] = 0; + out_3543458714162138959[38] = 0; + out_3543458714162138959[39] = 1; + out_3543458714162138959[40] = 0; + out_3543458714162138959[41] = 0; + out_3543458714162138959[42] = 0; + out_3543458714162138959[43] = 0; + out_3543458714162138959[44] = 0; + out_3543458714162138959[45] = 0; + out_3543458714162138959[46] = 0; + out_3543458714162138959[47] = 0; + out_3543458714162138959[48] = 0; + out_3543458714162138959[49] = 0; + out_3543458714162138959[50] = 0; + out_3543458714162138959[51] = 0; + out_3543458714162138959[52] = 0; + out_3543458714162138959[53] = 0; + out_3543458714162138959[54] = 0; + out_3543458714162138959[55] = 0; + out_3543458714162138959[56] = 0; + out_3543458714162138959[57] = 0; + out_3543458714162138959[58] = 0; + out_3543458714162138959[59] = 0; + out_3543458714162138959[60] = 0; + out_3543458714162138959[61] = 0; + out_3543458714162138959[62] = 1; + out_3543458714162138959[63] = 0; + out_3543458714162138959[64] = 0; + out_3543458714162138959[65] = 0; } #include #include @@ -1855,77 +1855,77 @@ void live_update_14(double *in_x, double *in_P, double *in_z, double *in_R, doub void live_update_33(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<3, 3, 0>(in_x, in_P, h_33, H_33, NULL, in_z, in_R, in_ea, MAHA_THRESH_33); } -void live_H(double *in_vec, double *out_4368495907718343571) { - H(in_vec, out_4368495907718343571); +void live_H(double *in_vec, double *out_6240008686817713408) { + H(in_vec, out_6240008686817713408); } -void live_err_fun(double *nom_x, double *delta_x, double *out_4465536791498929799) { - err_fun(nom_x, delta_x, out_4465536791498929799); +void live_err_fun(double *nom_x, double *delta_x, double *out_3690665086918622964) { + err_fun(nom_x, delta_x, out_3690665086918622964); } -void live_inv_err_fun(double *nom_x, double *true_x, double *out_4242153094211941637) { - inv_err_fun(nom_x, true_x, out_4242153094211941637); +void live_inv_err_fun(double *nom_x, double *true_x, double *out_8615868703535681088) { + inv_err_fun(nom_x, true_x, out_8615868703535681088); } -void live_H_mod_fun(double *state, double *out_8694534732588551911) { - H_mod_fun(state, out_8694534732588551911); +void live_H_mod_fun(double *state, double *out_1988291488770769521) { + H_mod_fun(state, out_1988291488770769521); } -void live_f_fun(double *state, double dt, double *out_331980123976991440) { - f_fun(state, dt, out_331980123976991440); +void live_f_fun(double *state, double dt, double *out_3263988285527381505) { + f_fun(state, dt, out_3263988285527381505); } -void live_F_fun(double *state, double dt, double *out_7523521905118560137) { - F_fun(state, dt, out_7523521905118560137); +void live_F_fun(double *state, double dt, double *out_4332092747232242913) { + F_fun(state, dt, out_4332092747232242913); } -void live_h_4(double *state, double *unused, double *out_874158167075593511) { - h_4(state, unused, out_874158167075593511); +void live_h_4(double *state, double *unused, double *out_6582152946104087701) { + h_4(state, unused, out_6582152946104087701); } -void live_H_4(double *state, double *unused, double *out_2890470532950944797) { - H_4(state, unused, out_2890470532950944797); +void live_H_4(double *state, double *unused, double *out_8426954437225368770) { + H_4(state, unused, out_8426954437225368770); } -void live_h_9(double *state, double *unused, double *out_7169843762143865122) { - h_9(state, unused, out_7169843762143865122); +void live_h_9(double *state, double *unused, double *out_7444569565063482614) { + h_9(state, unused, out_7444569565063482614); } -void live_H_9(double *state, double *unused, double *out_5779332085231024139) { - H_9(state, unused, out_5779332085231024139); +void live_H_9(double *state, double *unused, double *out_7130928084204103504) { + H_9(state, unused, out_7130928084204103504); } -void live_h_10(double *state, double *unused, double *out_3163124755553653720) { - h_10(state, unused, out_3163124755553653720); +void live_h_10(double *state, double *unused, double *out_1939752611965379146) { + h_10(state, unused, out_1939752611965379146); } -void live_H_10(double *state, double *unused, double *out_4896893583908803739) { - H_10(state, unused, out_4896893583908803739); +void live_H_10(double *state, double *unused, double *out_6385265893824183484) { + H_10(state, unused, out_6385265893824183484); } -void live_h_12(double *state, double *unused, double *out_6187507614461106032) { - h_12(state, unused, out_6187507614461106032); +void live_h_12(double *state, double *unused, double *out_7296993372404775801) { + h_12(state, unused, out_7296993372404775801); } -void live_H_12(double *state, double *unused, double *out_7889145227076156327) { - H_12(state, unused, out_7889145227076156327); +void live_H_12(double *state, double *unused, double *out_2352661322801732354) { + H_12(state, unused, out_2352661322801732354); } -void live_h_35(double *state, double *unused, double *out_4266066339955691863) { - h_35(state, unused, out_4266066339955691863); +void live_h_35(double *state, double *unused, double *out_947171662528612088) { + h_35(state, unused, out_947171662528612088); } -void live_H_35(double *state, double *unused, double *out_5143582194751142618) { - H_35(state, unused, out_5143582194751142618); +void live_H_35(double *state, double *unused, double *out_392901709523281355) { + H_35(state, unused, out_392901709523281355); } -void live_h_32(double *state, double *unused, double *out_9055313354289894635) { - h_32(state, unused, out_9055313354289894635); +void live_h_32(double *state, double *unused, double *out_2929900686975731664) { + h_32(state, unused, out_2929900686975731664); } -void live_H_32(double *state, double *unused, double *out_6388297375264292642) { - H_32(state, unused, out_6388297375264292642); +void live_H_32(double *state, double *unused, double *out_8907135071749521650) { + H_32(state, unused, out_8907135071749521650); } -void live_h_13(double *state, double *unused, double *out_7078564321862276630) { - h_13(state, unused, out_7078564321862276630); +void live_h_13(double *state, double *unused, double *out_4581312559012542837) { + h_13(state, unused, out_4581312559012542837); } -void live_H_13(double *state, double *unused, double *out_7646665591930494052) { - H_13(state, unused, out_7646665591930494052); +void live_H_13(double *state, double *unused, double *out_569470278268388809) { + H_13(state, unused, out_569470278268388809); } -void live_h_14(double *state, double *unused, double *out_7169843762143865122) { - h_14(state, unused, out_7169843762143865122); +void live_h_14(double *state, double *unused, double *out_7444569565063482614) { + h_14(state, unused, out_7444569565063482614); } -void live_H_14(double *state, double *unused, double *out_5779332085231024139) { - H_14(state, unused, out_5779332085231024139); +void live_H_14(double *state, double *unused, double *out_7130928084204103504) { + H_14(state, unused, out_7130928084204103504); } -void live_h_33(double *state, double *unused, double *out_3878198370963190653) { - h_33(state, unused, out_3878198370963190653); +void live_h_33(double *state, double *unused, double *out_7317084925230058116) { + h_33(state, unused, out_7317084925230058116); } -void live_H_33(double *state, double *unused, double *out_1993025190112285014) { - H_33(state, unused, out_1993025190112285014); +void live_H_33(double *state, double *unused, double *out_3543458714162138959) { + H_33(state, unused, out_3543458714162138959); } void live_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/live.h b/selfdrive/locationd/models/generated/live.h index cc2ca6526..b5b69513d 100644 --- a/selfdrive/locationd/models/generated/live.h +++ b/selfdrive/locationd/models/generated/live.h @@ -10,29 +10,29 @@ void live_update_32(double *in_x, double *in_P, double *in_z, double *in_R, doub void live_update_13(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void live_update_14(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void live_update_33(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void live_H(double *in_vec, double *out_4368495907718343571); -void live_err_fun(double *nom_x, double *delta_x, double *out_4465536791498929799); -void live_inv_err_fun(double *nom_x, double *true_x, double *out_4242153094211941637); -void live_H_mod_fun(double *state, double *out_8694534732588551911); -void live_f_fun(double *state, double dt, double *out_331980123976991440); -void live_F_fun(double *state, double dt, double *out_7523521905118560137); -void live_h_4(double *state, double *unused, double *out_874158167075593511); -void live_H_4(double *state, double *unused, double *out_2890470532950944797); -void live_h_9(double *state, double *unused, double *out_7169843762143865122); -void live_H_9(double *state, double *unused, double *out_5779332085231024139); -void live_h_10(double *state, double *unused, double *out_3163124755553653720); -void live_H_10(double *state, double *unused, double *out_4896893583908803739); -void live_h_12(double *state, double *unused, double *out_6187507614461106032); -void live_H_12(double *state, double *unused, double *out_7889145227076156327); -void live_h_35(double *state, double *unused, double *out_4266066339955691863); -void live_H_35(double *state, double *unused, double *out_5143582194751142618); -void live_h_32(double *state, double *unused, double *out_9055313354289894635); -void live_H_32(double *state, double *unused, double *out_6388297375264292642); -void live_h_13(double *state, double *unused, double *out_7078564321862276630); -void live_H_13(double *state, double *unused, double *out_7646665591930494052); -void live_h_14(double *state, double *unused, double *out_7169843762143865122); -void live_H_14(double *state, double *unused, double *out_5779332085231024139); -void live_h_33(double *state, double *unused, double *out_3878198370963190653); -void live_H_33(double *state, double *unused, double *out_1993025190112285014); +void live_H(double *in_vec, double *out_6240008686817713408); +void live_err_fun(double *nom_x, double *delta_x, double *out_3690665086918622964); +void live_inv_err_fun(double *nom_x, double *true_x, double *out_8615868703535681088); +void live_H_mod_fun(double *state, double *out_1988291488770769521); +void live_f_fun(double *state, double dt, double *out_3263988285527381505); +void live_F_fun(double *state, double dt, double *out_4332092747232242913); +void live_h_4(double *state, double *unused, double *out_6582152946104087701); +void live_H_4(double *state, double *unused, double *out_8426954437225368770); +void live_h_9(double *state, double *unused, double *out_7444569565063482614); +void live_H_9(double *state, double *unused, double *out_7130928084204103504); +void live_h_10(double *state, double *unused, double *out_1939752611965379146); +void live_H_10(double *state, double *unused, double *out_6385265893824183484); +void live_h_12(double *state, double *unused, double *out_7296993372404775801); +void live_H_12(double *state, double *unused, double *out_2352661322801732354); +void live_h_35(double *state, double *unused, double *out_947171662528612088); +void live_H_35(double *state, double *unused, double *out_392901709523281355); +void live_h_32(double *state, double *unused, double *out_2929900686975731664); +void live_H_32(double *state, double *unused, double *out_8907135071749521650); +void live_h_13(double *state, double *unused, double *out_4581312559012542837); +void live_H_13(double *state, double *unused, double *out_569470278268388809); +void live_h_14(double *state, double *unused, double *out_7444569565063482614); +void live_H_14(double *state, double *unused, double *out_7130928084204103504); +void live_h_33(double *state, double *unused, double *out_7317084925230058116); +void live_H_33(double *state, double *unused, double *out_3543458714162138959); void live_predict(double *in_x, double *in_P, double *in_Q, double dt); } \ No newline at end of file diff --git a/selfdrive/locationd/ubloxd b/selfdrive/locationd/ubloxd index 9b0e7c166..f68abe4a6 100755 Binary files a/selfdrive/locationd/ubloxd and b/selfdrive/locationd/ubloxd differ diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 99f484b8a..6f33cec2b 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -55,7 +55,7 @@ def manager_init() -> None: params.put_bool("RecordFront", True) if not params.get_bool("DisableRadar_Allow"): - params.delete("DisableRadar") + params.remove("DisableRadar") # set unset params for k, v in default_params: @@ -137,7 +137,9 @@ def manager_thread() -> None: dp_otisserv = params.get_bool('dp_otisserv') ignore += ['dmonitoringmodeld', 'dmonitoringd'] if params.get_bool('dp_jetson') else [] ignore += ['otisserv'] if not dp_otisserv else [] - ignore += ['gpxd'] if not dp_otisserv and not params.get_bool('dp_gpxd') else [] + dp_mapd = params.get_bool('dp_mapd') + ignore += ['mapd'] if not dp_mapd else [] + ignore += ['gpxd'] if not dp_otisserv and not dp_mapd and not params.get_bool('dp_gpxd') else [] ignore += ['uploader'] if not params.get_bool('dp_api_custom') and (int(params.get('dp_atl', encoding='utf8')) > 0 or params.get_bool('dp_jetson')) else [] if params.get("DongleId", encoding='utf8') in (None, UNREGISTERED_DONGLE_ID): diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 7b2540df0..7b652e4af 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -45,6 +45,7 @@ procs = [ # PythonProcess("navd", "selfdrive.navd.navd"), PythonProcess("pandad", "selfdrive.boardd.pandad", offroad=True), PythonProcess("paramsd", "selfdrive.locationd.paramsd"), + PythonProcess("pigeond", "selfdrive.sensord.pigeond", enabled=TICI), PythonProcess("plannerd", "selfdrive.controls.plannerd"), PythonProcess("radard", "selfdrive.controls.radard"), PythonProcess("thermald", "selfdrive.thermald.thermald", offroad=True), diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py index 8718744ca..e487e323c 100644 --- a/selfdrive/mapd/mapd.py +++ b/selfdrive/mapd/mapd.py @@ -12,6 +12,7 @@ from selfdrive.mapd.config import QUERY_RADIUS, MIN_DISTANCE_FOR_NEW_QUERY, FULL from system.swaglog import cloudlog # dp +import math from common.params import Params import json @@ -86,17 +87,46 @@ class MapD(): log = sm[sock] self.last_gps = log + skip_gps_query = False + location_valid = False # ignore the message if the fix is invalid if log.flags % 2 == 0: - return + skip_gps_query = True - self.last_gps_fix_timestamp = log.unixTimestampMillis # Unix TS. Milliseconds since January 1, 1970. - self.location_rad = np.radians(np.array([log.latitude, log.longitude], dtype=float)) - self.location_deg = (log.latitude, log.longitude) - self.bearing_rad = np.radians(log.bearingDeg, dtype=float) - self.gps_speed = log.speed - self.location_stdev = log.accuracy # log accuracies are presumably 1 standard deviation. + if not skip_gps_query: + self.last_gps_fix_timestamp = log.unixTimestampMillis # Unix TS. Milliseconds since January 1, 1970. + self.location_rad = np.radians(np.array([log.latitude, log.longitude], dtype=float)) + self.location_deg = (log.latitude, log.longitude) + self.bearing_rad = np.radians(log.bearingDeg, dtype=float) + self.gps_speed = log.speed + self.location_stdev = log.accuracy # log accuracies are presumably 1 standard deviation. + + sock = 'liveLocationKalman' + if sm.updated[sock] and sm.valid[sock]: + location = sm[sock] + location_valid = location.positionGeodetic.valid + + if location_valid: + _debug("Mapd: Using liveLocationKalman") + lat = float(location.positionGeodetic.value[0]) + lon = float(location.positionGeodetic.value[1]) + bearing = math.degrees(location.calibratedOrientationNED.value[2]) + + self.last_gps_fix_timestamp = location.unixTimestampMillis # Unix TS. Milliseconds since January 1, 1970. + self.location_rad = np.radians(np.array([lat, lon], dtype=float)) + self.location_deg = (lat, lon) + self.bearing_rad = np.radians(bearing, dtype=float) + self.gps_speed = sm['carState'].vEgo + self.location_stdev = 1.0 if log.accuracy > 5 else log.accuracy + + # self.last_gps.latitude = lat + # self.last_gps.longitude = lon + # self.last_gps.speed = self.gps_speed + # self.last_gps.bearingDeg = bearing + + if skip_gps_query and not location_valid: + return _debug('Mapd: ********* Got GPS fix' + f'Pos: {self.location_deg} +/- {self.location_stdev * 2.} mts.\n' @@ -275,7 +305,7 @@ def mapd_thread(sm=None, pm=None): # *** setup messaging if sm is None: - sm = messaging.SubMaster(['gpsLocationExternal', 'controlsState']) + sm = messaging.SubMaster(['gpsLocationExternal', 'controlsState', 'liveLocationKalman', 'carState']) if pm is None: pm = messaging.PubMaster(['liveMapData']) diff --git a/selfdrive/modeld/_modeld b/selfdrive/modeld/_modeld index 291bc3316..c537bd483 100755 Binary files a/selfdrive/modeld/_modeld and b/selfdrive/modeld/_modeld differ diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index d551bdf48..e2ee812e4 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -253,8 +253,8 @@ constexpr int NET_OUTPUT_SIZE = OUTPUT_SIZE + TEMPORAL_SIZE; // TODO: convert remaining arrays to std::array and update model runners struct ModelState { - ModelFrame *frame; - ModelFrame *wide_frame; + ModelFrame *frame = nullptr; + ModelFrame *wide_frame = nullptr; std::array output = {}; std::unique_ptr m; #ifdef DESIRE diff --git a/selfdrive/modeld/models/supercombo.thneed b/selfdrive/modeld/models/supercombo.thneed index c13c069f8..d8bbadf2a 100644 Binary files a/selfdrive/modeld/models/supercombo.thneed and b/selfdrive/modeld/models/supercombo.thneed differ diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py index 496c9ce3a..1c86e53ce 100755 --- a/selfdrive/navd/navd.py +++ b/selfdrive/navd/navd.py @@ -239,7 +239,7 @@ class RouteEngine: self.recompute_countdown = 0 else: cloudlog.warning("Destination reached") - Params().delete("NavDestination") + Params().remove("NavDestination") # Clear route if driving away from destination dist = self.nav_destination.distance_to(self.last_position) diff --git a/selfdrive/sensord/_sensord b/selfdrive/sensord/_sensord index 3892dd92e..76059abf6 100755 Binary files a/selfdrive/sensord/_sensord and b/selfdrive/sensord/_sensord differ diff --git a/selfdrive/sensord/pigeond.py b/selfdrive/sensord/pigeond.py new file mode 100755 index 000000000..95a27189d --- /dev/null +++ b/selfdrive/sensord/pigeond.py @@ -0,0 +1,255 @@ +#!/usr/bin/env python3 + +import sys +import time +import signal +import serial +import struct +import requests +import urllib.parse +from datetime import datetime + +from cereal import messaging +from common.params import Params +from system.swaglog import cloudlog +from selfdrive.hardware import TICI +from common.gpio import gpio_init, gpio_set +from selfdrive.hardware.tici.pins import GPIO + +UBLOX_TTY = "/dev/ttyHS0" + +UBLOX_ACK = b"\xb5\x62\x05\x01\x02\x00" +UBLOX_NACK = b"\xb5\x62\x05\x00\x02\x00" +UBLOX_SOS_ACK = b"\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x01\x00\x00\x00" +UBLOX_SOS_NACK = b"\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00" +UBLOX_BACKUP_RESTORE_MSG = b"\xb5\x62\x09\x14\x08\x00\x03" +UBLOX_ASSIST_ACK = b"\xb5\x62\x13\x60\x08\x00" + +def set_power(enabled): + gpio_init(GPIO.UBLOX_SAFEBOOT_N, True) + gpio_init(GPIO.UBLOX_PWR_EN, True) + gpio_init(GPIO.UBLOX_RST_N, True) + + gpio_set(GPIO.UBLOX_SAFEBOOT_N, True) + gpio_set(GPIO.UBLOX_PWR_EN, enabled) + gpio_set(GPIO.UBLOX_RST_N, enabled) + + +def add_ubx_checksum(msg): + A = B = 0 + for b in msg[2:]: + A = (A + b) % 256 + B = (B + A) % 256 + return msg + bytes([A, B]) + +def get_assistnow_messages(token): + # make request + # TODO: implement adding the last known location + r = requests.get("https://online-live2.services.u-blox.com/GetOnlineData.ashx", params=urllib.parse.urlencode({ + 'token': token, + 'gnss': 'gps,glo', + 'datatype': 'eph,alm,aux', + }, safe=':,'), timeout=5) + assert r.status_code == 200, "Got invalid status code" + dat = r.content + + # split up messages + msgs = [] + while len(dat) > 0: + assert dat[:2] == b"\xB5\x62" + msg_len = 6 + (dat[5] << 8 | dat[4]) + 2 + msgs.append(dat[:msg_len]) + dat = dat[msg_len:] + return msgs + + +class TTYPigeon(): + def __init__(self, path): + self.path = path + self.tty = serial.VTIMESerial(UBLOX_TTY, baudrate=9600, timeout=0) + + def send(self, dat): + self.tty.write(dat) + + def receive(self): + dat = b'' + while len(dat) < 0x1000: + d = self.tty.read(0x40) + dat += d + if len(d) == 0: + break + return dat + + def set_baud(self, baud): + self.tty.baudrate = baud + + def wait_for_ack(self, ack=UBLOX_ACK, nack=UBLOX_NACK, timeout=0.5): + dat = b'' + st = time.monotonic() + while True: + dat += self.receive() + if ack in dat: + cloudlog.debug("Received ACK from ublox") + return True + elif nack in dat: + cloudlog.error("Received NACK from ublox") + return False + elif time.monotonic() - st > timeout: + cloudlog.error("No response from ublox") + raise TimeoutError('No response from ublox') + time.sleep(0.001) + + def send_with_ack(self, dat, ack=UBLOX_ACK, nack=UBLOX_NACK): + self.send(dat) + self.wait_for_ack(ack, nack) + + def wait_for_backup_restore_status(self, timeout=1): + dat = b'' + st = time.monotonic() + while True: + dat += self.receive() + position = dat.find(UBLOX_BACKUP_RESTORE_MSG) + if position >= 0 and len(dat) >= position + 11: + return dat[position + 10] + elif time.monotonic() - st > timeout: + cloudlog.error("No backup restore response from ublox") + raise TimeoutError('No response from ublox') + time.sleep(0.001) + + +def initialize_pigeon(pigeon): + # try initializing a few times + for _ in range(10): + try: + pigeon.set_baud(9600) + + # up baud rate + pigeon.send(b"\x24\x50\x55\x42\x58\x2C\x34\x31\x2C\x31\x2C\x30\x30\x30\x37\x2C\x30\x30\x30\x33\x2C\x34\x36\x30\x38\x30\x30\x2C\x30\x2A\x31\x35\x0D\x0A") + time.sleep(0.1) + pigeon.set_baud(460800) + + # other configuration messages + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x03\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x01\x00\x00\x00\x00\x00\x1E\x7F") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x00\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x19\x35") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x01\x00\x00\x00\xC0\x08\x00\x00\x00\x08\x07\x00\x01\x00\x01\x00\x00\x00\x00\x00\xF4\x80") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x14\x00\x04\xFF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x1D\x85") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x00\x00\x06\x18") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x01\x08\x22") + pigeon.send_with_ack(b"\xB5\x62\x06\x00\x01\x00\x03\x0A\x24") + pigeon.send_with_ack(b"\xB5\x62\x06\x08\x06\x00\x64\x00\x01\x00\x00\x00\x79\x10") + pigeon.send_with_ack(b"\xB5\x62\x06\x24\x24\x00\x05\x00\x04\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x5A\x63") + pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x14\x00\x00\x00\x00\x00\x01\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x3C\x37") + pigeon.send_with_ack(b"\xB5\x62\x06\x39\x08\x00\xFF\xAD\x62\xAD\x1E\x63\x00\x00\x83\x0C") + pigeon.send_with_ack(b"\xB5\x62\x06\x23\x28\x00\x00\x00\x00\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x56\x24") + pigeon.send_with_ack(b"\xB5\x62\x06\x24\x00\x00\x2A\x84") + pigeon.send_with_ack(b"\xB5\x62\x06\x23\x00\x00\x29\x81") + pigeon.send_with_ack(b"\xB5\x62\x06\x1E\x00\x00\x24\x72") + pigeon.send_with_ack(b"\xB5\x62\x06\x39\x00\x00\x3F\xC3") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x01\x07\x01\x13\x51") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x15\x01\x22\x70") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x02\x13\x01\x20\x6C") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70") + pigeon.send_with_ack(b"\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74") + cloudlog.debug("pigeon configured") + + # try restoring almanac backup + pigeon.send(b"\xB5\x62\x09\x14\x00\x00\x1D\x60") + restore_status = pigeon.wait_for_backup_restore_status() + if restore_status == 2: + cloudlog.warning("almanac backup restored") + elif restore_status == 3: + cloudlog.warning("no almanac backup found") + else: + cloudlog.error(f"failed to restore almanac backup, status: {restore_status}") + + # sending time to ublox + t_now = datetime.utcnow() + if t_now >= datetime(2021, 6, 1): + cloudlog.warning("Sending current time to ublox") + + # UBX-MGA-INI-TIME_UTC + msg = add_ubx_checksum(b"\xB5\x62\x13\x40\x18\x00" + struct.pack(" 0: + if dat[0] == 0x00: + cloudlog.warning("received invalid data from ublox, re-initing!") + initialize_pigeon(pigeon) + continue + + # send out to socket + msg = messaging.new_message('ubloxRaw', len(dat)) + msg.ubloxRaw = dat[:] + pm.send('ubloxRaw', msg) + +if __name__ == "__main__": + main() diff --git a/selfdrive/ui/_ui b/selfdrive/ui/_ui index db3730780..4b74164bf 100755 Binary files a/selfdrive/ui/_ui and b/selfdrive/ui/_ui differ diff --git a/selfdrive/ui/qt/spinner b/selfdrive/ui/qt/spinner index 73c2bcbb3..0859eed42 100755 Binary files a/selfdrive/ui/qt/spinner and b/selfdrive/ui/qt/spinner differ diff --git a/selfdrive/ui/qt/text b/selfdrive/ui/qt/text index a970e3b79..e10e950fb 100755 Binary files a/selfdrive/ui/qt/text and b/selfdrive/ui/qt/text differ diff --git a/selfdrive/ui/soundd/_soundd b/selfdrive/ui/soundd/_soundd index e4e385aba..c872413a0 100755 Binary files a/selfdrive/ui/soundd/_soundd and b/selfdrive/ui/soundd/_soundd differ diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index 2559b2d26..072d320c1 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,6 +1,6 @@ { "English": "main_en", - "Português": "main_pt", + "Português": "main_pt-BR", "中文(繁體)": "main_zh-CHT", "中文(简体)": "main_zh-CHS", "한국어": "main_ko", diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts new file mode 100644 index 000000000..284208720 --- /dev/null +++ b/selfdrive/ui/translations/main_ar.ts @@ -0,0 +1,1323 @@ + + + + + AbstractAlert + + + Close + أغلق + + + + Snooze Update + تأخير التحديث + + + + Reboot and Update + إعادة التشغيل والتحديث + + + + AdvancedNetworking + + + Back + خلف + + + + Enable Tethering + تمكين الربط + + + + Tethering Password + كلمة مرور للربط + + + + + EDIT + تعديل + + + + Enter new tethering password + أدخل كلمة مرور جديدة للربط + + + + IP Address + عنوان IP + + + + Enable Roaming + تمكين التجوال + + + + APN Setting + إعداد APN + + + + Enter APN + أدخل APN + + + + leave blank for automatic configuration + اتركه فارغا للتكوين التلقائي + + + + ConfirmationDialog + + + + Ok + موافق + + + + Cancel + إلغاء + + + + DeclinePage + + + You must accept the Terms and Conditions in order to use openpilot. + يجب عليك قبول الشروط والأحكام من أجل استخدام openpilot. + + + + Back + خلف + + + + Decline, uninstall %1 + رفض ، قم بإلغاء تثبيت %1 + + + + DevicePanel + + + Dongle ID + معرف دونجل + + + + N/A + غير متاح + + + + Serial + التسلسلي + + + + Driver Camera + كاميرا السائق + + + + PREVIEW + لمح + + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + قم بمعاينة الكاميرا المواجهة للسائق للتأكد من أن نظام مراقبة السائق يتمتع برؤية جيدة. (يجب أن تكون السيارة معطلة) + + + + Reset Calibration + إعادة ضبط المعايرة + + + + RESET + إعادة تعيين + + + + Are you sure you want to reset calibration? + هل أنت متأكد أنك تريد إعادة ضبط المعايرة؟ + + + + Review Training Guide + مراجعة دليل التدريب + + + + REVIEW + مراجعة + + + + Review the rules, features, and limitations of openpilot + راجع القواعد والميزات والقيود الخاصة بـ openpilot + + + + Are you sure you want to review the training guide? + هل أنت متأكد أنك تريد مراجعة دليل التدريب؟ + + + + Regulatory + تنظيمية + + + + VIEW + عرض + + + + Change Language + تغيير اللغة + + + + CHANGE + تغيير + + + + Select a language + اختر لغة + + + + Reboot + اعادة التشغيل + + + + Power Off + أطفاء + + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + يتطلب openpilot أن يتم تركيب الجهاز في حدود 4 درجات يسارًا أو يمينًا و 5 درجات لأعلى أو 8 درجات لأسفل. يقوم برنامج openpilot بالمعايرة بشكل مستمر ، ونادراً ما تكون إعادة الضبط مطلوبة. + + + + Your device is pointed %1° %2 and %3° %4. + جهازك يشير %1° %2 و %3° %4. + + + + down + لأسفل + + + + up + إلى أعلى + + + + left + إلى اليسار + + + + right + إلى اليمين + + + + Are you sure you want to reboot? + هل أنت متأكد أنك تريد إعادة التشغيل؟ + + + + Disengage to Reboot + فك الارتباط لإعادة التشغيل + + + + Are you sure you want to power off? + هل أنت متأكد أنك تريد إيقاف التشغيل؟ + + + + Disengage to Power Off + فك الارتباط لإيقاف التشغيل + + + + DriveStats + + + Drives + أرقام القيادة + + + + Hours + ساعات + + + + ALL TIME + في كل وقت + + + + PAST WEEK + الأسبوع الماضي + + + + KM + كم + + + + Miles + اميال + + + + DriverViewScene + + + camera starting + بدء تشغيل الكاميرا + + + + InputDialog + + + Cancel + إلغاء + + + + Need at least %n character(s)! + + تحتاج على الأقل %n حرف! + تحتاج على الأقل %n حرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + تحتاج على الأقل %n احرف! + + + + + Installer + + + Installing... + جارٍ التثبيت ... + + + + Receiving objects: + استقبال الكائنات: + + + + Resolving deltas: + حل دلتا: + + + + Updating files: + جارٍ تحديث الملفات: + + + + MapETA + + + eta + eta + + + + min + دق + + + + hr + سع + + + + km + كم + + + + mi + مل + + + + MapInstructions + + + km + كم + + + + m + م + + + + mi + مل + + + + ft + قد + + + + MapPanel + + + Current Destination + الوجهة الحالية + + + + CLEAR + مسح + + + + Recent Destinations + الوجهات الأخيرة + + + + Try the Navigation Beta + جرب التنقل التجريبي + + + + Get turn-by-turn directions displayed and more with a comma +prime subscription. Sign up now: https://connect.comma.ai + احصل على الاتجاهات خطوة بخطوة معروضة والمزيد باستخدام comma +الاشتراك الرئيسي. اشترك الآن: https://connect.comma.ai + + + + No home +location set + لم يتم تعيين +موقع المنزل + + + + No work +location set + لم يتم تعيين +موقع العمل + + + + no recent destinations + لا توجد وجهات حديثة + + + + MapWindow + + + Map Loading + تحميل الخريطة + + + + Waiting for GPS + في انتظار GPS + + + + MultiOptionDialog + + + Select + اختر + + + + Cancel + إلغاء + + + + Networking + + + Advanced + متقدم + + + + Enter password + أدخل كلمة المرور + + + + + for "%1" + ل "%1" + + + + Wrong password + كلمة مرور خاطئة + + + + NvgWindow + + + km/h + km/h + + + + mph + mph + + + + + MAX + الأعلى + + + + + SPEED + سرعة + + + + + LIMIT + حد + + + + OffroadHome + + + UPDATE + تحديث + + + + ALERTS + تنبيهات + + + + ALERT + تنبيه + + + + PairingPopup + + + Pair your device to your comma account + قم بإقران جهازك بحساب comma الخاص بك + + + + Go to https://connect.comma.ai on your phone + اذهب إلى https://connect.comma.ai من هاتفك + + + + Click "add new device" and scan the QR code on the right + انقر على "إضافة جهاز جديد" وامسح رمز الاستجابة السريعة على اليمين + + + + Bookmark connect.comma.ai to your home screen to use it like an app + ضع إشارة مرجعية على connect.comma.ai على شاشتك الرئيسية لاستخدامه مثل أي تطبيق + + + + PrimeAdWidget + + + Upgrade Now + قم بالترقية الآن + + + + Become a comma prime member at connect.comma.ai + كن عضوًا comme prime في connect.comma.ai + + + + PRIME FEATURES: + ميزات PRIME: + + + + Remote access + الوصول عن بعد + + + + 1 year of storage + سنة واحدة من التخزين + + + + Developer perks + امتيازات المطور + + + + PrimeUserWidget + + + ✓ SUBSCRIBED + ✓ مشترك + + + + comma prime + comma prime + + + + CONNECT.COMMA.AI + CONNECT.COMMA.AI + + + + COMMA POINTS + COMMA POINTS + + + + QObject + + + Reboot + اعادة التشغيل + + + + Exit + أغلق + + + + dashcam + dashcam + + + + openpilot + openpilot + + + + %n minute(s) ago + + منذ %n دقيقة + منذ %n دقيقة + منذ %n دقائق + منذ %n دقائق + منذ %n دقائق + منذ %n دقائق + + + + + %n hour(s) ago + + منذ %n ساعة + منذ %n ساعة + منذ %n ساعات + منذ %n ساعات + منذ %n ساعات + منذ %n ساعات + + + + + %n day(s) ago + + منذ %n يوم + منذ %n يوم + منذ %n ايام + منذ %n ايام + منذ %n ايام + منذ %n ايام + + + + + Reset + + + Reset failed. Reboot to try again. + فشل إعادة التعيين. أعد التشغيل للمحاولة مرة أخرى. + + + + Are you sure you want to reset your device? + هل أنت متأكد أنك تريد إعادة ضبط جهازك؟ + + + + Resetting device... + جارٍ إعادة ضبط الجهاز ... + + + + System Reset + إعادة تعيين النظام + + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + تم تشغيل إعادة تعيين النظام. اضغط على تأكيد لمسح كل المحتوى والإعدادات. اضغط على إلغاء لاستئناف التمهيد. + + + + Cancel + إلغاء + + + + Reboot + اعادة التشغيل + + + + Confirm + تأكيد + + + + Unable to mount data partition. Press confirm to reset your device. + تعذر تحميل قسم البيانات. اضغط على تأكيد لإعادة ضبط جهازك. + + + + RichTextDialog + + + Ok + موافق + + + + SettingsWindow + + + × + x + + + + Device + جهاز + + + + + Network + شبكة الاتصال + + + + Toggles + التبديل + + + + Software + برمجة + + + + Navigation + ملاحة + + + + Setup + + + WARNING: Low Voltage + تحذير: الجهد المنخفض + + + + Power your device in a car with a harness or proceed at your own risk. + قم بتشغيل جهازك في سيارة باستخدام أداة تثبيت أو المضي قدمًا على مسؤوليتك الخاصة. + + + + Power off + اطفئ الجهاز + + + + + + Continue + أكمل + + + + Getting Started + ابدء + + + + Before we get on the road, let’s finish installation and cover some details. + قبل أن ننطلق على الطريق ، دعنا ننتهي من التثبيت ونغطي بعض التفاصيل. + + + + Connect to Wi-Fi + اتصل بشبكة Wi-Fi + + + + + Back + خلف + + + + Continue without Wi-Fi + استمر بدون Wi-Fi + + + + Waiting for internet + في انتظار الاتصال بالإنترنت + + + + Choose Software to Install + اختر البرنامج المراد تثبيته + + + + Dashcam + Dashcam + + + + Custom Software + برامج مخصصة + + + + Enter URL + إدخال عنوان الموقع + + + + for Custom Software + للبرامج المخصصة + + + + Downloading... + جارى التحميل... + + + + Download Failed + فشل التنزيل + + + + Ensure the entered URL is valid, and the device’s internet connection is good. + تأكد من أن عنوان موقع الويب الذي تم إدخاله صالح ، وأن اتصال الجهاز بالإنترنت جيد. + + + + Reboot device + إعادة تشغيل الجهاز + + + + Start over + ابدأ من جديد + + + + SetupWidget + + + Finish Setup + إنهاء الإعداد + + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + قم بإقران جهازك بفاصلة connect (connect.comma.ai) واطلب عرض comma prime الخاص بك. + + + + Pair device + إقران الجهاز + + + + Sidebar + + + + CONNECT + الاتصال + + + + OFFLINE + غير متصل + + + + + ONLINE + متصل + + + + ERROR + خطأ + + + + + + TEMP + درجة الحرارة + + + + HIGH + عالي + + + + GOOD + جيد + + + + OK + موافق + + + + VEHICLE + مركبة + + + + NO + لا + + + + PANDA + PANDA + + + + GPS + GPS + + + + SEARCH + بحث + + + + -- + -- + + + + Wi-Fi + Wi-Fi + + + + ETH + ETH + + + + 2G + 2G + + + + 3G + 3G + + + + LTE + LTE + + + + 5G + 5G + + + + SoftwarePanel + + + Git Branch + Git Branch + + + + Git Commit + Git Commit + + + + OS Version + إصدار نظام التشغيل + + + + Version + إصدار + + + + Last Update Check + التحقق من آخر تحديث + + + + The last time openpilot successfully checked for an update. The updater only runs while the car is off. + آخر مرة نجح برنامج openpilot في التحقق من التحديث. يعمل المحدث فقط أثناء إيقاف تشغيل السيارة. + + + + Check for Update + فحص التحديثات + + + + CHECKING + تدقيق + + + + Switch Branch + تبديل الفرع + + + + ENTER + أدخل + + + + + The new branch will be pulled the next time the updater runs. + سيتم سحب الفرع الجديد في المرة التالية التي يتم فيها تشغيل أداة التحديث. + + + + Enter branch name + أدخل اسم الفرع + + + + UNINSTALL + الغاء التثبيت + + + + Uninstall %1 + الغاء التثبيت %1 + + + + Are you sure you want to uninstall? + هل أنت متأكد أنك تريد إلغاء التثبيت؟ + + + + failed to fetch update + فشل في جلب التحديث + + + + + CHECK + تأكد الان + + + + SshControl + + + SSH Keys + SSH Keys + + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + تحذير: هذا يمنح SSH الوصول إلى جميع المفاتيح العامة في إعدادات GitHub. لا تدخل أبدًا اسم مستخدم GitHub بخلاف اسم المستخدم الخاص بك. لن يطلب منك موظف comma أبدًا إضافة اسم مستخدم GitHub الخاص به. + + + + + ADD + أضف + + + + Enter your GitHub username + أدخل اسم مستخدم GitHub الخاص بك + + + + LOADING + جار التحميل + + + + REMOVE + نزع + + + + Username '%1' has no keys on GitHub + لا يحتوي اسم المستخدم '%1' على مفاتيح على GitHub + + + + Request timed out + انتهت مهلة الطلب + + + + Username '%1' doesn't exist on GitHub + اسم المستخدم '%1' غير موجود على GitHub + + + + SshToggle + + + Enable SSH + تفعيل SSH + + + + TermsPage + + + Terms & Conditions + البنود و الظروف + + + + Decline + انحدار + + + + Scroll to accept + قم بالتمرير للقبول + + + + Agree + موافق + + + + TogglesPanel + + + Enable openpilot + تمكين openpilot + + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + استخدم نظام الطيار المفتوح للتحكم التكيفي في ثبات السرعة والحفاظ على مساعدة السائق. انتباهك مطلوب في جميع الأوقات لاستخدام هذه الميزة. يسري تغيير هذا الإعداد عند إيقاف تشغيل السيارة. + + + + Enable Lane Departure Warnings + قم بتمكين تحذيرات مغادرة حارة السير + + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + تلقي تنبيهات للتوجه مرة أخرى إلى الحارة عندما تنجرف سيارتك فوق خط المسار المكتشف دون تنشيط إشارة الانعطاف أثناء القيادة لمسافة تزيد عن 31 ميلاً في الساعة (50 كم / ساعة). + + + + Use Metric System + استخدم النظام المتري + + + + Display speed in km/h instead of mph. + عرض السرعة بالكيلو متر في الساعة بدلاً من ميل في الساعة. + + + + Record and Upload Driver Camera + تسجيل وتحميل كاميرا السائق + + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + قم بتحميل البيانات من الكاميرا المواجهة للسائق وساعد في تحسين خوارزمية مراقبة السائق. + + + + Disengage On Accelerator Pedal + فك الارتباط على دواسة التسريع + + + + When enabled, pressing the accelerator pedal will disengage openpilot. + عند التمكين ، سيؤدي الضغط على دواسة الوقود إلى فصل الطيار المفتوح. + + + + Show ETA in 24h Format + إظهار الوقت المقدر للوصول بتنسيق 24 ساعة + + + + Use 24h format instead of am/pm + استخدم تنسيق 24 ساعة بدلاً من صباحًا / مساءً + + + + Show Map on Left Side of UI + إظهار الخريطة على الجانب الأيسر من واجهة المستخدم + + + + Show map on left side when in split screen view. + إظهار الخريطة على الجانب الأيسر عندما تكون في طريقة عرض الشاشة المنقسمة. + + + + openpilot Longitudinal Control + openpilot التحكم الطولي + + + + openpilot will disable the car's radar and will take over control of gas and brakes. Warning: this disables AEB! + سوف يقوم برنامج openpilot بتعطيل رادار السيارة وسيتولى التحكم في الغاز والمكابح. تحذير: هذا يعطل AEB! + + + + Updater + + + Update Required + مطلوب التحديث + + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + مطلوب تحديث نظام التشغيل. قم بتوصيل جهازك بشبكة Wi-Fi للحصول على أسرع تجربة تحديث. حجم التنزيل 1 غيغابايت تقريبًا. + + + + Connect to Wi-Fi + اتصل بشبكة Wi-Fi + + + + Install + ثبيت + + + + Back + خلف + + + + Loading... + جار التحميل... + + + + Reboot + اعادة التشغيل + + + + Update failed + فشل التحديث + + + + WifiUI + + + + Scanning for networks... + جارٍ البحث عن شبكات ... + + + + CONNECTING... + جارٍ الاتصال ... + + + + FORGET + نزع + + + + Forget Wi-Fi Network "%1"? + نزع شبكة اWi-Fi "%1"? + + + diff --git a/selfdrive/ui/translations/main_pt.ts b/selfdrive/ui/translations/main_pt-BR.ts similarity index 100% rename from selfdrive/ui/translations/main_pt.ts rename to selfdrive/ui/translations/main_pt-BR.ts diff --git a/selfdrive/updated.py b/selfdrive/updated.py index bdec818ae..8658cb257 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -118,7 +118,7 @@ def set_params(new_version: bool, failed_count: int, exception: Optional[str]) - pass if exception is None: - params.delete("LastUpdateException") + params.remove("LastUpdateException") else: params.put("LastUpdateException", exception) diff --git a/system/camerad/camerad b/system/camerad/camerad index af402c1c9..3ef6fb7dc 100755 Binary files a/system/camerad/camerad and b/system/camerad/camerad differ diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index 766f1daf1..ff7b6b737 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -87,7 +87,7 @@ def snapshot(): subprocess.check_call(["pgrep", "camerad"]) print("Camerad already running") params.put_bool("IsTakingSnapshot", False) - params.delete("Offroad_IsTakingSnapshot") + params.remove("Offroad_IsTakingSnapshot") return None, None except subprocess.CalledProcessError: pass diff --git a/system/clocksd/clocksd b/system/clocksd/clocksd index be63bc4e4..57fcdb286 100755 Binary files a/system/clocksd/clocksd and b/system/clocksd/clocksd differ