diff --git a/proto b/proto index fe04cb6445..fa204080ed 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit fe04cb64453477d8d9479f7ac3c56c2f58e0bbd5 +Subproject commit fa204080ed60fd28127f2e30513dc02c604e90f9 diff --git a/src/backend/src/generated/telemetry/telemetry.pb.cc b/src/backend/src/generated/telemetry/telemetry.pb.cc index 30cdcfb8c3..8bd3a83a88 100644 --- a/src/backend/src/generated/telemetry/telemetry.pb.cc +++ b/src/backend/src/generated/telemetry/telemetry.pb.cc @@ -2979,7 +2979,7 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_telemetry_2ftelemetry_2eproto: ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::DistanceSensor, minimum_distance_m_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::DistanceSensor, maximum_distance_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::DistanceSensor, maximum_distance_m_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::DistanceSensor, current_distance_m_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::PositionNed, _internal_metadata_), @@ -3514,214 +3514,214 @@ const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] PROTOBUF_SE "k.rpc.telemetry.Covariance\"j\n\010MavFrame\022\023" "\n\017MAV_FRAME_UNDEF\020\000\022\026\n\022MAV_FRAME_BODY_NE" "D\020\010\022\030\n\024MAV_FRAME_VISION_NED\020\020\022\027\n\023MAV_FRA" - "ME_ESTIM_NED\020\022\"}\n\016DistanceSensor\022#\n\022mini" - "mum_distance_m\030\001 \001(\002B\007\202\265\030\003NaN\022!\n\020maximum" - "_distance\030\002 \001(\002B\007\202\265\030\003NaN\022#\n\022current_dist" - "ance_m\030\003 \001(\002B\007\202\265\030\003NaN\"Y\n\013PositionNed\022\030\n\007" - "north_m\030\001 \001(\002B\007\202\265\030\003NaN\022\027\n\006east_m\030\002 \001(\002B\007" - "\202\265\030\003NaN\022\027\n\006down_m\030\003 \001(\002B\007\202\265\030\003NaN\"D\n\013Velo" - "cityNed\022\021\n\tnorth_m_s\030\001 \001(\002\022\020\n\010east_m_s\030\002" - " \001(\002\022\020\n\010down_m_s\030\003 \001(\002\"\177\n\023PositionVeloci" - "tyNed\0223\n\010position\030\001 \001(\0132!.mavsdk.rpc.tel" - "emetry.PositionNed\0223\n\010velocity\030\002 \001(\0132!.m" - "avsdk.rpc.telemetry.VelocityNed\"r\n\013Groun" - "dTruth\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n" - "\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolut" - "e_altitude_m\030\003 \001(\002B\007\202\265\030\003NaN\"x\n\020Fixedwing" - "Metrics\022\035\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$" - "\n\023throttle_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016" - "climb_rate_m_s\030\003 \001(\002B\007\202\265\030\003NaN\"i\n\017Acceler" - "ationFrd\022\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003NaN\022" - "\033\n\nright_m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m_s" - "2\030\003 \001(\002B\007\202\265\030\003NaN\"o\n\022AngularVelocityFrd\022\036" - "\n\rforward_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_" - "rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001(\002" - "B\007\202\265\030\003NaN\"m\n\020MagneticFieldFrd\022\036\n\rforward" - "_gauss\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002 \001" - "(\002B\007\202\265\030\003NaN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003NaN" - "\"\365\001\n\003Imu\022\?\n\020acceleration_frd\030\001 \001(\0132%.mav" - "sdk.rpc.telemetry.AccelerationFrd\022F\n\024ang" - "ular_velocity_frd\030\002 \001(\0132(.mavsdk.rpc.tel" - "emetry.AngularVelocityFrd\022B\n\022magnetic_fi" - "eld_frd\030\003 \001(\0132&.mavsdk.rpc.telemetry.Mag" - "neticFieldFrd\022!\n\020temperature_degc\030\004 \001(\002B" - "\007\202\265\030\003NaN\"\211\002\n\017TelemetryResult\022<\n\006result\030\001" - " \001(\0162,.mavsdk.rpc.telemetry.TelemetryRes" - "ult.Result\022\022\n\nresult_str\030\002 \001(\t\"\243\001\n\006Resul" - "t\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020" - "\001\022\024\n\020RESULT_NO_SYSTEM\020\002\022\033\n\027RESULT_CONNEC" - "TION_ERROR\020\003\022\017\n\013RESULT_BUSY\020\004\022\031\n\025RESULT_" - "COMMAND_DENIED\020\005\022\022\n\016RESULT_TIMEOUT\020\006*\244\001\n" - "\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n\017FIX_TYP" - "E_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022\023\n\017FIX_T" - "YPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGPS\020\004\022\026\n\022F" - "IX_TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE_RTK_FIXE" - "D\020\006*\206\003\n\nFlightMode\022\027\n\023FLIGHT_MODE_UNKNOW" - "N\020\000\022\025\n\021FLIGHT_MODE_READY\020\001\022\027\n\023FLIGHT_MOD" - "E_TAKEOFF\020\002\022\024\n\020FLIGHT_MODE_HOLD\020\003\022\027\n\023FLI" - "GHT_MODE_MISSION\020\004\022 \n\034FLIGHT_MODE_RETURN" - "_TO_LAUNCH\020\005\022\024\n\020FLIGHT_MODE_LAND\020\006\022\030\n\024FL" - "IGHT_MODE_OFFBOARD\020\007\022\031\n\025FLIGHT_MODE_FOLL" - "OW_ME\020\010\022\026\n\022FLIGHT_MODE_MANUAL\020\t\022\026\n\022FLIGH" - "T_MODE_ALTCTL\020\n\022\026\n\022FLIGHT_MODE_POSCTL\020\013\022" - "\024\n\020FLIGHT_MODE_ACRO\020\014\022\032\n\026FLIGHT_MODE_STA" - "BILIZED\020\r\022\031\n\025FLIGHT_MODE_RATTITUDE\020\016*\371\001\n" - "\016StatusTextType\022\032\n\026STATUS_TEXT_TYPE_DEBU" - "G\020\000\022\031\n\025STATUS_TEXT_TYPE_INFO\020\001\022\033\n\027STATUS" - "_TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_TEXT_TYPE_" - "WARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_ERROR\020\004\022\035\n" - "\031STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n\026STATUS_T" - "EXT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT_TYPE_EME" - "RGENCY\020\007*\223\001\n\013LandedState\022\030\n\024LANDED_STATE" - "_UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_GROUND\020\001\022\027" - "\n\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LANDED_STATE_" - "TAKING_OFF\020\003\022\030\n\024LANDED_STATE_LANDING\020\0042\375" - ",\n\020TelemetryService\022o\n\021SubscribePosition" - "\022..mavsdk.rpc.telemetry.SubscribePositio" - "nRequest\032&.mavsdk.rpc.telemetry.Position" - "Response\"\0000\001\022c\n\rSubscribeHome\022*.mavsdk.r" - "pc.telemetry.SubscribeHomeRequest\032\".mavs" - "dk.rpc.telemetry.HomeResponse\"\0000\001\022f\n\016Sub" - "scribeInAir\022+.mavsdk.rpc.telemetry.Subsc" - "ribeInAirRequest\032#.mavsdk.rpc.telemetry." - "InAirResponse\"\0000\001\022x\n\024SubscribeLandedStat" - "e\0221.mavsdk.rpc.telemetry.SubscribeLanded" - "StateRequest\032).mavsdk.rpc.telemetry.Land" - "edStateResponse\"\0000\001\022f\n\016SubscribeArmed\022+." - "mavsdk.rpc.telemetry.SubscribeArmedReque" - "st\032#.mavsdk.rpc.telemetry.ArmedResponse\"" - "\0000\001\022\215\001\n\033SubscribeAttitudeQuaternion\0228.ma" - "vsdk.rpc.telemetry.SubscribeAttitudeQuat" - "ernionRequest\0320.mavsdk.rpc.telemetry.Att" - "itudeQuaternionResponse\"\0000\001\022~\n\026Subscribe" - "AttitudeEuler\0223.mavsdk.rpc.telemetry.Sub" - "scribeAttitudeEulerRequest\032+.mavsdk.rpc." - "telemetry.AttitudeEulerResponse\"\0000\001\022\250\001\n$" - "SubscribeAttitudeAngularVelocityBody\022A.m" - "avsdk.rpc.telemetry.SubscribeAttitudeAng" - "ularVelocityBodyRequest\0329.mavsdk.rpc.tel" - "emetry.AttitudeAngularVelocityBodyRespon" - "se\"\0000\001\022\237\001\n!SubscribeCameraAttitudeQuater" - "nion\022>.mavsdk.rpc.telemetry.SubscribeCam" - "eraAttitudeQuaternionRequest\0326.mavsdk.rp" - "c.telemetry.CameraAttitudeQuaternionResp" - "onse\"\0000\001\022\220\001\n\034SubscribeCameraAttitudeEule" - "r\0229.mavsdk.rpc.telemetry.SubscribeCamera" - "AttitudeEulerRequest\0321.mavsdk.rpc.teleme" - "try.CameraAttitudeEulerResponse\"\0000\001\022x\n\024S" - "ubscribeVelocityNed\0221.mavsdk.rpc.telemet" - "ry.SubscribeVelocityNedRequest\032).mavsdk." - "rpc.telemetry.VelocityNedResponse\"\0000\001\022l\n" - "\020SubscribeGpsInfo\022-.mavsdk.rpc.telemetry" - ".SubscribeGpsInfoRequest\032%.mavsdk.rpc.te" - "lemetry.GpsInfoResponse\"\0000\001\022l\n\020Subscribe" - "Battery\022-.mavsdk.rpc.telemetry.Subscribe" - "BatteryRequest\032%.mavsdk.rpc.telemetry.Ba" - "tteryResponse\"\0000\001\022u\n\023SubscribeFlightMode" - "\0220.mavsdk.rpc.telemetry.SubscribeFlightM" - "odeRequest\032(.mavsdk.rpc.telemetry.Flight" - "ModeResponse\"\0000\001\022i\n\017SubscribeHealth\022,.ma" - "vsdk.rpc.telemetry.SubscribeHealthReques" - "t\032$.mavsdk.rpc.telemetry.HealthResponse\"" - "\0000\001\022o\n\021SubscribeRcStatus\022..mavsdk.rpc.te" - "lemetry.SubscribeRcStatusRequest\032&.mavsd" - "k.rpc.telemetry.RcStatusResponse\"\0000\001\022u\n\023" - "SubscribeStatusText\0220.mavsdk.rpc.telemet" - "ry.SubscribeStatusTextRequest\032(.mavsdk.r" - "pc.telemetry.StatusTextResponse\"\0000\001\022\226\001\n\036" - "SubscribeActuatorControlTarget\022;.mavsdk." - "rpc.telemetry.SubscribeActuatorControlTa" - "rgetRequest\0323.mavsdk.rpc.telemetry.Actua" - "torControlTargetResponse\"\0000\001\022\223\001\n\035Subscri" - "beActuatorOutputStatus\022:.mavsdk.rpc.tele" - "metry.SubscribeActuatorOutputStatusReque" - "st\0322.mavsdk.rpc.telemetry.ActuatorOutput" - "StatusResponse\"\0000\001\022o\n\021SubscribeOdometry\022" - "..mavsdk.rpc.telemetry.SubscribeOdometry" - "Request\032&.mavsdk.rpc.telemetry.OdometryR" - "esponse\"\0000\001\022\220\001\n\034SubscribePositionVelocit" - "yNed\0229.mavsdk.rpc.telemetry.SubscribePos" - "itionVelocityNedRequest\0321.mavsdk.rpc.tel" - "emetry.PositionVelocityNedResponse\"\0000\001\022x" - "\n\024SubscribeGroundTruth\0221.mavsdk.rpc.tele" - "metry.SubscribeGroundTruthRequest\032).mavs" - "dk.rpc.telemetry.GroundTruthResponse\"\0000\001" - "\022\207\001\n\031SubscribeFixedwingMetrics\0226.mavsdk." - "rpc.telemetry.SubscribeFixedwingMetricsR" - "equest\032..mavsdk.rpc.telemetry.FixedwingM" - "etricsResponse\"\0000\001\022`\n\014SubscribeImu\022).mav" - "sdk.rpc.telemetry.SubscribeImuRequest\032!." - "mavsdk.rpc.telemetry.ImuResponse\"\0000\001\022x\n\024" - "SubscribeHealthAllOk\0221.mavsdk.rpc.teleme" - "try.SubscribeHealthAllOkRequest\032).mavsdk" - ".rpc.telemetry.HealthAllOkResponse\"\0000\001\022~" - "\n\026SubscribeUnixEpochTime\0223.mavsdk.rpc.te" - "lemetry.SubscribeUnixEpochTimeRequest\032+." - "mavsdk.rpc.telemetry.UnixEpochTimeRespon" - "se\"\0000\001\022\201\001\n\027SubscribeDistanceSensor\0224.mav" - "sdk.rpc.telemetry.SubscribeDistanceSenso" - "rRequest\032,.mavsdk.rpc.telemetry.Distance" - "SensorResponse\"\0000\001\022p\n\017SetRatePosition\022,." - "mavsdk.rpc.telemetry.SetRatePositionRequ" - "est\032-.mavsdk.rpc.telemetry.SetRatePositi" - "onResponse\"\000\022d\n\013SetRateHome\022(.mavsdk.rpc" - ".telemetry.SetRateHomeRequest\032).mavsdk.r" - "pc.telemetry.SetRateHomeResponse\"\000\022g\n\014Se" - "tRateInAir\022).mavsdk.rpc.telemetry.SetRat" - "eInAirRequest\032*.mavsdk.rpc.telemetry.Set" - "RateInAirResponse\"\000\022y\n\022SetRateLandedStat" - "e\022/.mavsdk.rpc.telemetry.SetRateLandedSt" - "ateRequest\0320.mavsdk.rpc.telemetry.SetRat" - "eLandedStateResponse\"\000\022p\n\017SetRateAttitud" - "e\022,.mavsdk.rpc.telemetry.SetRateAttitude" - "Request\032-.mavsdk.rpc.telemetry.SetRateAt" - "titudeResponse\"\000\022\202\001\n\025SetRateCameraAttitu" - "de\0222.mavsdk.rpc.telemetry.SetRateCameraA" - "ttitudeRequest\0323.mavsdk.rpc.telemetry.Se" - "tRateCameraAttitudeResponse\"\000\022y\n\022SetRate" - "VelocityNed\022/.mavsdk.rpc.telemetry.SetRa" - "teVelocityNedRequest\0320.mavsdk.rpc.teleme" - "try.SetRateVelocityNedResponse\"\000\022m\n\016SetR" - "ateGpsInfo\022+.mavsdk.rpc.telemetry.SetRat" - "eGpsInfoRequest\032,.mavsdk.rpc.telemetry.S" - "etRateGpsInfoResponse\"\000\022m\n\016SetRateBatter" - "y\022+.mavsdk.rpc.telemetry.SetRateBatteryR" - "equest\032,.mavsdk.rpc.telemetry.SetRateBat" - "teryResponse\"\000\022p\n\017SetRateRcStatus\022,.mavs" - "dk.rpc.telemetry.SetRateRcStatusRequest\032" - "-.mavsdk.rpc.telemetry.SetRateRcStatusRe" - "sponse\"\000\022\227\001\n\034SetRateActuatorControlTarge" - "t\0229.mavsdk.rpc.telemetry.SetRateActuator" - "ControlTargetRequest\032:.mavsdk.rpc.teleme" - "try.SetRateActuatorControlTargetResponse" - "\"\000\022\224\001\n\033SetRateActuatorOutputStatus\0228.mav" - "sdk.rpc.telemetry.SetRateActuatorOutputS" - "tatusRequest\0329.mavsdk.rpc.telemetry.SetR" - "ateActuatorOutputStatusResponse\"\000\022p\n\017Set" - "RateOdometry\022,.mavsdk.rpc.telemetry.SetR" - "ateOdometryRequest\032-.mavsdk.rpc.telemetr" - "y.SetRateOdometryResponse\"\000\022\221\001\n\032SetRateP" - "ositionVelocityNed\0227.mavsdk.rpc.telemetr" - "y.SetRatePositionVelocityNedRequest\0328.ma" - "vsdk.rpc.telemetry.SetRatePositionVeloci" - "tyNedResponse\"\000\022y\n\022SetRateGroundTruth\022/." - "mavsdk.rpc.telemetry.SetRateGroundTruthR" - "equest\0320.mavsdk.rpc.telemetry.SetRateGro" - "undTruthResponse\"\000\022\210\001\n\027SetRateFixedwingM" - "etrics\0224.mavsdk.rpc.telemetry.SetRateFix" - "edwingMetricsRequest\0325.mavsdk.rpc.teleme" - "try.SetRateFixedwingMetricsResponse\"\000\022a\n" - "\nSetRateImu\022\'.mavsdk.rpc.telemetry.SetRa" - "teImuRequest\032(.mavsdk.rpc.telemetry.SetR" - "ateImuResponse\"\000\022\177\n\024SetRateUnixEpochTime" - "\0221.mavsdk.rpc.telemetry.SetRateUnixEpoch" - "TimeRequest\0322.mavsdk.rpc.telemetry.SetRa" - "teUnixEpochTimeResponse\"\000\022\202\001\n\025SetRateDis" - "tanceSensor\0222.mavsdk.rpc.telemetry.SetRa" - "teDistanceSensorRequest\0323.mavsdk.rpc.tel" - "emetry.SetRateDistanceSensorResponse\"\000B%" - "\n\023io.mavsdk.telemetryB\016TelemetryProtob\006p" - "roto3" + "ME_ESTIM_NED\020\022\"\177\n\016DistanceSensor\022#\n\022mini" + "mum_distance_m\030\001 \001(\002B\007\202\265\030\003NaN\022#\n\022maximum" + "_distance_m\030\002 \001(\002B\007\202\265\030\003NaN\022#\n\022current_di" + "stance_m\030\003 \001(\002B\007\202\265\030\003NaN\"Y\n\013PositionNed\022\030" + "\n\007north_m\030\001 \001(\002B\007\202\265\030\003NaN\022\027\n\006east_m\030\002 \001(\002" + "B\007\202\265\030\003NaN\022\027\n\006down_m\030\003 \001(\002B\007\202\265\030\003NaN\"D\n\013Ve" + "locityNed\022\021\n\tnorth_m_s\030\001 \001(\002\022\020\n\010east_m_s" + "\030\002 \001(\002\022\020\n\010down_m_s\030\003 \001(\002\"\177\n\023PositionVelo" + "cityNed\0223\n\010position\030\001 \001(\0132!.mavsdk.rpc.t" + "elemetry.PositionNed\0223\n\010velocity\030\002 \001(\0132!" + ".mavsdk.rpc.telemetry.VelocityNed\"r\n\013Gro" + "undTruth\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022" + "\036\n\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absol" + "ute_altitude_m\030\003 \001(\002B\007\202\265\030\003NaN\"x\n\020Fixedwi" + "ngMetrics\022\035\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN" + "\022$\n\023throttle_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037" + "\n\016climb_rate_m_s\030\003 \001(\002B\007\202\265\030\003NaN\"i\n\017Accel" + "erationFrd\022\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003Na" + "N\022\033\n\nright_m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m" + "_s2\030\003 \001(\002B\007\202\265\030\003NaN\"o\n\022AngularVelocityFrd" + "\022\036\n\rforward_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013righ" + "t_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001" + "(\002B\007\202\265\030\003NaN\"m\n\020MagneticFieldFrd\022\036\n\rforwa" + "rd_gauss\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002" + " \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003N" + "aN\"\365\001\n\003Imu\022\?\n\020acceleration_frd\030\001 \001(\0132%.m" + "avsdk.rpc.telemetry.AccelerationFrd\022F\n\024a" + "ngular_velocity_frd\030\002 \001(\0132(.mavsdk.rpc.t" + "elemetry.AngularVelocityFrd\022B\n\022magnetic_" + "field_frd\030\003 \001(\0132&.mavsdk.rpc.telemetry.M" + "agneticFieldFrd\022!\n\020temperature_degc\030\004 \001(" + "\002B\007\202\265\030\003NaN\"\211\002\n\017TelemetryResult\022<\n\006result" + "\030\001 \001(\0162,.mavsdk.rpc.telemetry.TelemetryR" + "esult.Result\022\022\n\nresult_str\030\002 \001(\t\"\243\001\n\006Res" + "ult\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCES" + "S\020\001\022\024\n\020RESULT_NO_SYSTEM\020\002\022\033\n\027RESULT_CONN" + "ECTION_ERROR\020\003\022\017\n\013RESULT_BUSY\020\004\022\031\n\025RESUL" + "T_COMMAND_DENIED\020\005\022\022\n\016RESULT_TIMEOUT\020\006*\244" + "\001\n\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n\017FIX_T" + "YPE_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022\023\n\017FIX" + "_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGPS\020\004\022\026\n" + "\022FIX_TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE_RTK_FI" + "XED\020\006*\206\003\n\nFlightMode\022\027\n\023FLIGHT_MODE_UNKN" + "OWN\020\000\022\025\n\021FLIGHT_MODE_READY\020\001\022\027\n\023FLIGHT_M" + "ODE_TAKEOFF\020\002\022\024\n\020FLIGHT_MODE_HOLD\020\003\022\027\n\023F" + "LIGHT_MODE_MISSION\020\004\022 \n\034FLIGHT_MODE_RETU" + "RN_TO_LAUNCH\020\005\022\024\n\020FLIGHT_MODE_LAND\020\006\022\030\n\024" + "FLIGHT_MODE_OFFBOARD\020\007\022\031\n\025FLIGHT_MODE_FO" + "LLOW_ME\020\010\022\026\n\022FLIGHT_MODE_MANUAL\020\t\022\026\n\022FLI" + "GHT_MODE_ALTCTL\020\n\022\026\n\022FLIGHT_MODE_POSCTL\020" + "\013\022\024\n\020FLIGHT_MODE_ACRO\020\014\022\032\n\026FLIGHT_MODE_S" + "TABILIZED\020\r\022\031\n\025FLIGHT_MODE_RATTITUDE\020\016*\371" + "\001\n\016StatusTextType\022\032\n\026STATUS_TEXT_TYPE_DE" + "BUG\020\000\022\031\n\025STATUS_TEXT_TYPE_INFO\020\001\022\033\n\027STAT" + "US_TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_TEXT_TYP" + "E_WARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_ERROR\020\004\022" + "\035\n\031STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n\026STATUS" + "_TEXT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT_TYPE_E" + "MERGENCY\020\007*\223\001\n\013LandedState\022\030\n\024LANDED_STA" + "TE_UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_GROUND\020\001" + "\022\027\n\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LANDED_STAT" + "E_TAKING_OFF\020\003\022\030\n\024LANDED_STATE_LANDING\020\004" + "2\375,\n\020TelemetryService\022o\n\021SubscribePositi" + "on\022..mavsdk.rpc.telemetry.SubscribePosit" + "ionRequest\032&.mavsdk.rpc.telemetry.Positi" + "onResponse\"\0000\001\022c\n\rSubscribeHome\022*.mavsdk" + ".rpc.telemetry.SubscribeHomeRequest\032\".ma" + "vsdk.rpc.telemetry.HomeResponse\"\0000\001\022f\n\016S" + "ubscribeInAir\022+.mavsdk.rpc.telemetry.Sub" + "scribeInAirRequest\032#.mavsdk.rpc.telemetr" + "y.InAirResponse\"\0000\001\022x\n\024SubscribeLandedSt" + "ate\0221.mavsdk.rpc.telemetry.SubscribeLand" + "edStateRequest\032).mavsdk.rpc.telemetry.La" + "ndedStateResponse\"\0000\001\022f\n\016SubscribeArmed\022" + "+.mavsdk.rpc.telemetry.SubscribeArmedReq" + "uest\032#.mavsdk.rpc.telemetry.ArmedRespons" + "e\"\0000\001\022\215\001\n\033SubscribeAttitudeQuaternion\0228." + "mavsdk.rpc.telemetry.SubscribeAttitudeQu" + "aternionRequest\0320.mavsdk.rpc.telemetry.A" + "ttitudeQuaternionResponse\"\0000\001\022~\n\026Subscri" + "beAttitudeEuler\0223.mavsdk.rpc.telemetry.S" + "ubscribeAttitudeEulerRequest\032+.mavsdk.rp" + "c.telemetry.AttitudeEulerResponse\"\0000\001\022\250\001" + "\n$SubscribeAttitudeAngularVelocityBody\022A" + ".mavsdk.rpc.telemetry.SubscribeAttitudeA" + "ngularVelocityBodyRequest\0329.mavsdk.rpc.t" + "elemetry.AttitudeAngularVelocityBodyResp" + "onse\"\0000\001\022\237\001\n!SubscribeCameraAttitudeQuat" + "ernion\022>.mavsdk.rpc.telemetry.SubscribeC" + "ameraAttitudeQuaternionRequest\0326.mavsdk." + "rpc.telemetry.CameraAttitudeQuaternionRe" + "sponse\"\0000\001\022\220\001\n\034SubscribeCameraAttitudeEu" + "ler\0229.mavsdk.rpc.telemetry.SubscribeCame" + "raAttitudeEulerRequest\0321.mavsdk.rpc.tele" + "metry.CameraAttitudeEulerResponse\"\0000\001\022x\n" + "\024SubscribeVelocityNed\0221.mavsdk.rpc.telem" + "etry.SubscribeVelocityNedRequest\032).mavsd" + "k.rpc.telemetry.VelocityNedResponse\"\0000\001\022" + "l\n\020SubscribeGpsInfo\022-.mavsdk.rpc.telemet" + "ry.SubscribeGpsInfoRequest\032%.mavsdk.rpc." + "telemetry.GpsInfoResponse\"\0000\001\022l\n\020Subscri" + "beBattery\022-.mavsdk.rpc.telemetry.Subscri" + "beBatteryRequest\032%.mavsdk.rpc.telemetry." + "BatteryResponse\"\0000\001\022u\n\023SubscribeFlightMo" + "de\0220.mavsdk.rpc.telemetry.SubscribeFligh" + "tModeRequest\032(.mavsdk.rpc.telemetry.Flig" + "htModeResponse\"\0000\001\022i\n\017SubscribeHealth\022,." + "mavsdk.rpc.telemetry.SubscribeHealthRequ" + "est\032$.mavsdk.rpc.telemetry.HealthRespons" + "e\"\0000\001\022o\n\021SubscribeRcStatus\022..mavsdk.rpc." + "telemetry.SubscribeRcStatusRequest\032&.mav" + "sdk.rpc.telemetry.RcStatusResponse\"\0000\001\022u" + "\n\023SubscribeStatusText\0220.mavsdk.rpc.telem" + "etry.SubscribeStatusTextRequest\032(.mavsdk" + ".rpc.telemetry.StatusTextResponse\"\0000\001\022\226\001" + "\n\036SubscribeActuatorControlTarget\022;.mavsd" + "k.rpc.telemetry.SubscribeActuatorControl" + "TargetRequest\0323.mavsdk.rpc.telemetry.Act" + "uatorControlTargetResponse\"\0000\001\022\223\001\n\035Subsc" + "ribeActuatorOutputStatus\022:.mavsdk.rpc.te" + "lemetry.SubscribeActuatorOutputStatusReq" + "uest\0322.mavsdk.rpc.telemetry.ActuatorOutp" + "utStatusResponse\"\0000\001\022o\n\021SubscribeOdometr" + "y\022..mavsdk.rpc.telemetry.SubscribeOdomet" + "ryRequest\032&.mavsdk.rpc.telemetry.Odometr" + "yResponse\"\0000\001\022\220\001\n\034SubscribePositionVeloc" + "ityNed\0229.mavsdk.rpc.telemetry.SubscribeP" + "ositionVelocityNedRequest\0321.mavsdk.rpc.t" + "elemetry.PositionVelocityNedResponse\"\0000\001" + "\022x\n\024SubscribeGroundTruth\0221.mavsdk.rpc.te" + "lemetry.SubscribeGroundTruthRequest\032).ma" + "vsdk.rpc.telemetry.GroundTruthResponse\"\000" + "0\001\022\207\001\n\031SubscribeFixedwingMetrics\0226.mavsd" + "k.rpc.telemetry.SubscribeFixedwingMetric" + "sRequest\032..mavsdk.rpc.telemetry.Fixedwin" + "gMetricsResponse\"\0000\001\022`\n\014SubscribeImu\022).m" + "avsdk.rpc.telemetry.SubscribeImuRequest\032" + "!.mavsdk.rpc.telemetry.ImuResponse\"\0000\001\022x" + "\n\024SubscribeHealthAllOk\0221.mavsdk.rpc.tele" + "metry.SubscribeHealthAllOkRequest\032).mavs" + "dk.rpc.telemetry.HealthAllOkResponse\"\0000\001" + "\022~\n\026SubscribeUnixEpochTime\0223.mavsdk.rpc." + "telemetry.SubscribeUnixEpochTimeRequest\032" + "+.mavsdk.rpc.telemetry.UnixEpochTimeResp" + "onse\"\0000\001\022\201\001\n\027SubscribeDistanceSensor\0224.m" + "avsdk.rpc.telemetry.SubscribeDistanceSen" + "sorRequest\032,.mavsdk.rpc.telemetry.Distan" + "ceSensorResponse\"\0000\001\022p\n\017SetRatePosition\022" + ",.mavsdk.rpc.telemetry.SetRatePositionRe" + "quest\032-.mavsdk.rpc.telemetry.SetRatePosi" + "tionResponse\"\000\022d\n\013SetRateHome\022(.mavsdk.r" + "pc.telemetry.SetRateHomeRequest\032).mavsdk" + ".rpc.telemetry.SetRateHomeResponse\"\000\022g\n\014" + "SetRateInAir\022).mavsdk.rpc.telemetry.SetR" + "ateInAirRequest\032*.mavsdk.rpc.telemetry.S" + "etRateInAirResponse\"\000\022y\n\022SetRateLandedSt" + "ate\022/.mavsdk.rpc.telemetry.SetRateLanded" + "StateRequest\0320.mavsdk.rpc.telemetry.SetR" + "ateLandedStateResponse\"\000\022p\n\017SetRateAttit" + "ude\022,.mavsdk.rpc.telemetry.SetRateAttitu" + "deRequest\032-.mavsdk.rpc.telemetry.SetRate" + "AttitudeResponse\"\000\022\202\001\n\025SetRateCameraAtti" + "tude\0222.mavsdk.rpc.telemetry.SetRateCamer" + "aAttitudeRequest\0323.mavsdk.rpc.telemetry." + "SetRateCameraAttitudeResponse\"\000\022y\n\022SetRa" + "teVelocityNed\022/.mavsdk.rpc.telemetry.Set" + "RateVelocityNedRequest\0320.mavsdk.rpc.tele" + "metry.SetRateVelocityNedResponse\"\000\022m\n\016Se" + "tRateGpsInfo\022+.mavsdk.rpc.telemetry.SetR" + "ateGpsInfoRequest\032,.mavsdk.rpc.telemetry" + ".SetRateGpsInfoResponse\"\000\022m\n\016SetRateBatt" + "ery\022+.mavsdk.rpc.telemetry.SetRateBatter" + "yRequest\032,.mavsdk.rpc.telemetry.SetRateB" + "atteryResponse\"\000\022p\n\017SetRateRcStatus\022,.ma" + "vsdk.rpc.telemetry.SetRateRcStatusReques" + "t\032-.mavsdk.rpc.telemetry.SetRateRcStatus" + "Response\"\000\022\227\001\n\034SetRateActuatorControlTar" + "get\0229.mavsdk.rpc.telemetry.SetRateActuat" + "orControlTargetRequest\032:.mavsdk.rpc.tele" + "metry.SetRateActuatorControlTargetRespon" + "se\"\000\022\224\001\n\033SetRateActuatorOutputStatus\0228.m" + "avsdk.rpc.telemetry.SetRateActuatorOutpu" + "tStatusRequest\0329.mavsdk.rpc.telemetry.Se" + "tRateActuatorOutputStatusResponse\"\000\022p\n\017S" + "etRateOdometry\022,.mavsdk.rpc.telemetry.Se" + "tRateOdometryRequest\032-.mavsdk.rpc.teleme" + "try.SetRateOdometryResponse\"\000\022\221\001\n\032SetRat" + "ePositionVelocityNed\0227.mavsdk.rpc.teleme" + "try.SetRatePositionVelocityNedRequest\0328." + "mavsdk.rpc.telemetry.SetRatePositionVelo" + "cityNedResponse\"\000\022y\n\022SetRateGroundTruth\022" + "/.mavsdk.rpc.telemetry.SetRateGroundTrut" + "hRequest\0320.mavsdk.rpc.telemetry.SetRateG" + "roundTruthResponse\"\000\022\210\001\n\027SetRateFixedwin" + "gMetrics\0224.mavsdk.rpc.telemetry.SetRateF" + "ixedwingMetricsRequest\0325.mavsdk.rpc.tele" + "metry.SetRateFixedwingMetricsResponse\"\000\022" + "a\n\nSetRateImu\022\'.mavsdk.rpc.telemetry.Set" + "RateImuRequest\032(.mavsdk.rpc.telemetry.Se" + "tRateImuResponse\"\000\022\177\n\024SetRateUnixEpochTi" + "me\0221.mavsdk.rpc.telemetry.SetRateUnixEpo" + "chTimeRequest\0322.mavsdk.rpc.telemetry.Set" + "RateUnixEpochTimeResponse\"\000\022\202\001\n\025SetRateD" + "istanceSensor\0222.mavsdk.rpc.telemetry.Set" + "RateDistanceSensorRequest\0323.mavsdk.rpc.t" + "elemetry.SetRateDistanceSensorResponse\"\000" + "B%\n\023io.mavsdk.telemetryB\016TelemetryProtob" + "\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_telemetry_2ftelemetry_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, @@ -3853,7 +3853,7 @@ static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_tel static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_telemetry_2ftelemetry_2eproto_once; static bool descriptor_table_telemetry_2ftelemetry_2eproto_initialized = false; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_telemetry_2ftelemetry_2eproto = { - &descriptor_table_telemetry_2ftelemetry_2eproto_initialized, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", 16365, + &descriptor_table_telemetry_2ftelemetry_2eproto_initialized, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", 16367, &descriptor_table_telemetry_2ftelemetry_2eproto_once, descriptor_table_telemetry_2ftelemetry_2eproto_sccs, descriptor_table_telemetry_2ftelemetry_2eproto_deps, 122, 1, schemas, file_default_instances, TableStruct_telemetry_2ftelemetry_2eproto::offsets, file_level_metadata_telemetry_2ftelemetry_2eproto, 122, file_level_enum_descriptors_telemetry_2ftelemetry_2eproto, file_level_service_descriptors_telemetry_2ftelemetry_2eproto, @@ -25572,10 +25572,10 @@ const char* DistanceSensor::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE ptr += sizeof(float); } else goto handle_unusual; continue; - // float maximum_distance = 2 [(.mavsdk.options.default_value) = "NaN"]; + // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; case 2: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) { - maximum_distance_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + maximum_distance_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else goto handle_unusual; continue; @@ -25618,10 +25618,10 @@ ::PROTOBUF_NAMESPACE_ID::uint8* DistanceSensor::_InternalSerialize( target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_minimum_distance_m(), target); } - // float maximum_distance = 2 [(.mavsdk.options.default_value) = "NaN"]; - if (!(this->maximum_distance() <= 0 && this->maximum_distance() >= 0)) { + // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + if (!(this->maximum_distance_m() <= 0 && this->maximum_distance_m() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_maximum_distance(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_maximum_distance_m(), target); } // float current_distance_m = 3 [(.mavsdk.options.default_value) = "NaN"]; @@ -25651,8 +25651,8 @@ size_t DistanceSensor::ByteSizeLong() const { total_size += 1 + 4; } - // float maximum_distance = 2 [(.mavsdk.options.default_value) = "NaN"]; - if (!(this->maximum_distance() <= 0 && this->maximum_distance() >= 0)) { + // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + if (!(this->maximum_distance_m() <= 0 && this->maximum_distance_m() >= 0)) { total_size += 1 + 4; } @@ -25695,8 +25695,8 @@ void DistanceSensor::MergeFrom(const DistanceSensor& from) { if (!(from.minimum_distance_m() <= 0 && from.minimum_distance_m() >= 0)) { _internal_set_minimum_distance_m(from._internal_minimum_distance_m()); } - if (!(from.maximum_distance() <= 0 && from.maximum_distance() >= 0)) { - _internal_set_maximum_distance(from._internal_maximum_distance()); + if (!(from.maximum_distance_m() <= 0 && from.maximum_distance_m() >= 0)) { + _internal_set_maximum_distance_m(from._internal_maximum_distance_m()); } if (!(from.current_distance_m() <= 0 && from.current_distance_m() >= 0)) { _internal_set_current_distance_m(from._internal_current_distance_m()); @@ -25725,7 +25725,7 @@ void DistanceSensor::InternalSwap(DistanceSensor* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); swap(minimum_distance_m_, other->minimum_distance_m_); - swap(maximum_distance_, other->maximum_distance_); + swap(maximum_distance_m_, other->maximum_distance_m_); swap(current_distance_m_, other->current_distance_m_); } diff --git a/src/backend/src/generated/telemetry/telemetry.pb.h b/src/backend/src/generated/telemetry/telemetry.pb.h index 320fdb9333..f6380b9e32 100644 --- a/src/backend/src/generated/telemetry/telemetry.pb.h +++ b/src/backend/src/generated/telemetry/telemetry.pb.h @@ -15462,7 +15462,7 @@ class DistanceSensor : enum : int { kMinimumDistanceMFieldNumber = 1, - kMaximumDistanceFieldNumber = 2, + kMaximumDistanceMFieldNumber = 2, kCurrentDistanceMFieldNumber = 3, }; // float minimum_distance_m = 1 [(.mavsdk.options.default_value) = "NaN"]; @@ -15474,13 +15474,13 @@ class DistanceSensor : void _internal_set_minimum_distance_m(float value); public: - // float maximum_distance = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_maximum_distance(); - float maximum_distance() const; - void set_maximum_distance(float value); + // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_maximum_distance_m(); + float maximum_distance_m() const; + void set_maximum_distance_m(float value); private: - float _internal_maximum_distance() const; - void _internal_set_maximum_distance(float value); + float _internal_maximum_distance_m() const; + void _internal_set_maximum_distance_m(float value); public: // float current_distance_m = 3 [(.mavsdk.options.default_value) = "NaN"]; @@ -15498,7 +15498,7 @@ class DistanceSensor : ::PROTOBUF_NAMESPACE_ID::internal::InternalMetadataWithArena _internal_metadata_; float minimum_distance_m_; - float maximum_distance_; + float maximum_distance_m_; float current_distance_m_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; @@ -21965,24 +21965,24 @@ inline void DistanceSensor::set_minimum_distance_m(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.DistanceSensor.minimum_distance_m) } -// float maximum_distance = 2 [(.mavsdk.options.default_value) = "NaN"]; -inline void DistanceSensor::clear_maximum_distance() { - maximum_distance_ = 0; +// float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; +inline void DistanceSensor::clear_maximum_distance_m() { + maximum_distance_m_ = 0; } -inline float DistanceSensor::_internal_maximum_distance() const { - return maximum_distance_; +inline float DistanceSensor::_internal_maximum_distance_m() const { + return maximum_distance_m_; } -inline float DistanceSensor::maximum_distance() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.DistanceSensor.maximum_distance) - return _internal_maximum_distance(); +inline float DistanceSensor::maximum_distance_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.DistanceSensor.maximum_distance_m) + return _internal_maximum_distance_m(); } -inline void DistanceSensor::_internal_set_maximum_distance(float value) { +inline void DistanceSensor::_internal_set_maximum_distance_m(float value) { - maximum_distance_ = value; + maximum_distance_m_ = value; } -inline void DistanceSensor::set_maximum_distance(float value) { - _internal_set_maximum_distance(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.DistanceSensor.maximum_distance) +inline void DistanceSensor::set_maximum_distance_m(float value) { + _internal_set_maximum_distance_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.DistanceSensor.maximum_distance_m) } // float current_distance_m = 3 [(.mavsdk.options.default_value) = "NaN"]; diff --git a/src/backend/src/plugins/telemetry/telemetry_service_impl.h b/src/backend/src/plugins/telemetry/telemetry_service_impl.h index ed50491ab3..275b223263 100644 --- a/src/backend/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/backend/src/plugins/telemetry/telemetry_service_impl.h @@ -762,7 +762,7 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv rpc_obj->set_minimum_distance_m(distance_sensor.minimum_distance_m); - rpc_obj->set_maximum_distance(distance_sensor.maximum_distance); + rpc_obj->set_maximum_distance_m(distance_sensor.maximum_distance_m); rpc_obj->set_current_distance_m(distance_sensor.current_distance_m); @@ -776,7 +776,7 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv obj.minimum_distance_m = distance_sensor.minimum_distance_m(); - obj.maximum_distance = distance_sensor.maximum_distance(); + obj.maximum_distance_m = distance_sensor.maximum_distance_m(); obj.current_distance_m = distance_sensor.current_distance_m(); diff --git a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h index 3e39d6234a..32bbc6b1ed 100644 --- a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -554,7 +554,7 @@ class Telemetry : public PluginBase { struct DistanceSensor { float minimum_distance_m{ float(NAN)}; /**< @brief Minimum distance the sensor can measure, NaN if unknown. */ - float maximum_distance{ + float maximum_distance_m{ float(NAN)}; /**< @brief Maximum distance the sensor can measure, NaN if unknown. */ float current_distance_m{ float(NAN)}; /**< @brief Current distance reading, NaN if unknown. */ diff --git a/src/plugins/telemetry/telemetry.cpp b/src/plugins/telemetry/telemetry.cpp index cae60a1952..3e4f6c0e6a 100644 --- a/src/plugins/telemetry/telemetry.cpp +++ b/src/plugins/telemetry/telemetry.cpp @@ -829,8 +829,8 @@ bool operator==(const Telemetry::DistanceSensor& lhs, const Telemetry::DistanceS { return ((std::isnan(rhs.minimum_distance_m) && std::isnan(lhs.minimum_distance_m)) || rhs.minimum_distance_m == lhs.minimum_distance_m) && - ((std::isnan(rhs.maximum_distance) && std::isnan(lhs.maximum_distance)) || - rhs.maximum_distance == lhs.maximum_distance) && + ((std::isnan(rhs.maximum_distance_m) && std::isnan(lhs.maximum_distance_m)) || + rhs.maximum_distance_m == lhs.maximum_distance_m) && ((std::isnan(rhs.current_distance_m) && std::isnan(lhs.current_distance_m)) || rhs.current_distance_m == lhs.current_distance_m); } @@ -840,7 +840,7 @@ std::ostream& operator<<(std::ostream& str, Telemetry::DistanceSensor const& dis str << std::setprecision(15); str << "distance_sensor:" << '\n' << "{\n"; str << " minimum_distance_m: " << distance_sensor.minimum_distance_m << '\n'; - str << " maximum_distance: " << distance_sensor.maximum_distance << '\n'; + str << " maximum_distance_m: " << distance_sensor.maximum_distance_m << '\n'; str << " current_distance_m: " << distance_sensor.current_distance_m << '\n'; str << '}'; return str; diff --git a/src/plugins/telemetry/telemetry_impl.cpp b/src/plugins/telemetry/telemetry_impl.cpp index d6f7d99668..0c0b9bf826 100644 --- a/src/plugins/telemetry/telemetry_impl.cpp +++ b/src/plugins/telemetry/telemetry_impl.cpp @@ -1108,9 +1108,9 @@ void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message) Telemetry::DistanceSensor distance_sensor_struct{}; - distance_sensor_struct.min_distance = distance_sensor_msg.min_distance; - distance_sensor_struct.max_distance = distance_sensor_msg.max_distance; - distance_sensor_struct.current_distance = distance_sensor_msg.current_distance; + distance_sensor_struct.minimum_distance_m = distance_sensor_msg.minimum_distance_m; + distance_sensor_struct.maximum_distance_m = distance_sensor_msg.maximum_distance_m; + distance_sensor_struct.current_distance_m = distance_sensor_msg.current_distance_m; set_distance_sensor(distance_sensor_struct);