From fbc8d01a7e96c25ec0e9bc70058d012735461273 Mon Sep 17 00:00:00 2001
From: Oleg Kalachev <okalachev@gmail.com>
Date: Fri, 22 Feb 2019 18:41:17 +0300
Subject: [PATCH] Rename distance_sensor.covariance to variance

---
 msg/distance_sensor.msg                                     | 2 +-
 src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp             | 2 +-
 src/drivers/distance_sensor/leddar_one/leddar_one.cpp       | 2 +-
 src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp         | 2 +-
 src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp         | 2 +-
 src/drivers/distance_sensor/mb12xx/mb12xx.cpp               | 2 +-
 src/drivers/distance_sensor/sf0x/sf0x.cpp                   | 2 +-
 src/drivers/distance_sensor/sf1xx/sf1xx.cpp                 | 2 +-
 src/drivers/distance_sensor/srf02/srf02.cpp                 | 2 +-
 src/drivers/distance_sensor/teraranger/teraranger.cpp       | 2 +-
 src/drivers/distance_sensor/tfmini/tfmini.cpp               | 2 +-
 src/drivers/distance_sensor/ulanding/ulanding.cpp           | 4 ++--
 src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp             | 2 +-
 src/drivers/px4flow/px4flow.cpp                             | 2 +-
 src/modules/local_position_estimator/sensors/lidar.cpp      | 2 +-
 src/modules/local_position_estimator/sensors/sonar.cpp      | 2 +-
 src/modules/mavlink/mavlink_messages.cpp                    | 2 +-
 src/modules/mavlink/mavlink_receiver.cpp                    | 6 +++---
 src/modules/simulator/simulator_mavlink.cpp                 | 2 +-
 .../df_bebop_rangefinder_wrapper.cpp                        | 2 +-
 .../drivers/df_isl29501_wrapper/df_isl29501_wrapper.cpp     | 2 +-
 .../posix/drivers/df_trone_wrapper/df_trone_wrapper.cpp     | 2 +-
 22 files changed, 25 insertions(+), 25 deletions(-)

diff --git a/msg/distance_sensor.msg b/msg/distance_sensor.msg
index 6e636160c5..ca688ca79b 100644
--- a/msg/distance_sensor.msg
+++ b/msg/distance_sensor.msg
@@ -5,7 +5,7 @@ uint64 timestamp		# time since system start (microseconds)
 float32 min_distance		# Minimum distance the sensor can measure (in m)
 float32 max_distance		# Maximum distance the sensor can measure (in m)
 float32 current_distance	# Current distance reading (in m)
-float32 covariance		# Measurement covariance (in m^2), 0 for unknown / invalid readings
+float32 variance		# Measurement variance (in m^2), 0 for unknown / invalid readings
 int8 signal_quality		# Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality.
 
 uint8 type			# Type from MAV_DISTANCE_SENSOR enum
diff --git a/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp b/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp
index 611ece114e..1c61c93fbf 100644
--- a/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp
+++ b/src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp
@@ -399,7 +399,7 @@ CM8JL65::collect()
 	report.current_distance = _distance_mm / 1000.0f;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
index 70678a5137..6b5ce4f493 100644
--- a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
+++ b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
@@ -436,7 +436,7 @@ void leddar_one::_publish(uint16_t distance_mm)
 	report.current_distance = ((float)distance_mm / 1000.0f);
 	report.min_distance = MIN_DISTANCE;
 	report.max_distance = MAX_DISTANCE;
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	report.id = 0;
 
diff --git a/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp b/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp
index 31b97dcc7f..e16effa511 100644
--- a/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp
+++ b/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp
@@ -540,7 +540,7 @@ int LidarLiteI2C::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = signal_quality;
 	report.type =
 		distance_sensor_s::MAV_DISTANCE_SENSOR_LASER;		// the sensor is in fact a laser + sonar but there is no enum for this
diff --git a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
index be1281c6a7..bd0ee07634 100644
--- a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
+++ b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
@@ -178,7 +178,7 @@ int LidarLitePWM::measure()
 	_range.max_distance = get_maximum_distance();
 	_range.min_distance = get_minimum_distance();
 	_range.current_distance = float(_pwm.pulse_width) * 1e-3f;   /* 10 usec = 1 cm distance for LIDAR-Lite */
-	_range.covariance = 0.0f;
+	_range.variance = 0.0f;
 	_range.orientation = _rotation;
 	/* TODO: set proper ID */
 	_range.id = 0;
diff --git a/src/drivers/distance_sensor/mb12xx/mb12xx.cpp b/src/drivers/distance_sensor/mb12xx/mb12xx.cpp
index d79fbb08cf..dcfc75dc05 100644
--- a/src/drivers/distance_sensor/mb12xx/mb12xx.cpp
+++ b/src/drivers/distance_sensor/mb12xx/mb12xx.cpp
@@ -507,7 +507,7 @@ MB12XX::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/sf0x/sf0x.cpp b/src/drivers/distance_sensor/sf0x/sf0x.cpp
index 4614bb2e48..0e60b8a0f9 100644
--- a/src/drivers/distance_sensor/sf0x/sf0x.cpp
+++ b/src/drivers/distance_sensor/sf0x/sf0x.cpp
@@ -519,7 +519,7 @@ SF0X::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/sf1xx/sf1xx.cpp b/src/drivers/distance_sensor/sf1xx/sf1xx.cpp
index ba67d56fae..56c3ccd607 100644
--- a/src/drivers/distance_sensor/sf1xx/sf1xx.cpp
+++ b/src/drivers/distance_sensor/sf1xx/sf1xx.cpp
@@ -507,7 +507,7 @@ SF1XX::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/srf02/srf02.cpp b/src/drivers/distance_sensor/srf02/srf02.cpp
index d749d18929..9f504b3cf0 100644
--- a/src/drivers/distance_sensor/srf02/srf02.cpp
+++ b/src/drivers/distance_sensor/srf02/srf02.cpp
@@ -510,7 +510,7 @@ SRF02::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/teraranger/teraranger.cpp b/src/drivers/distance_sensor/teraranger/teraranger.cpp
index 1766a62625..3cfbeb959d 100644
--- a/src/drivers/distance_sensor/teraranger/teraranger.cpp
+++ b/src/drivers/distance_sensor/teraranger/teraranger.cpp
@@ -588,7 +588,7 @@ TERARANGER::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/tfmini/tfmini.cpp b/src/drivers/distance_sensor/tfmini/tfmini.cpp
index c1e30e4af8..e771c68041 100644
--- a/src/drivers/distance_sensor/tfmini/tfmini.cpp
+++ b/src/drivers/distance_sensor/tfmini/tfmini.cpp
@@ -540,7 +540,7 @@ TFMINI::collect()
 	report.current_distance = distance_m;
 	report.min_distance = get_minimum_distance();
 	report.max_distance = get_maximum_distance();
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 	/* TODO: set proper ID */
 	report.id = 0;
diff --git a/src/drivers/distance_sensor/ulanding/ulanding.cpp b/src/drivers/distance_sensor/ulanding/ulanding.cpp
index 9c3e870310..b22ce466cd 100644
--- a/src/drivers/distance_sensor/ulanding/ulanding.cpp
+++ b/src/drivers/distance_sensor/ulanding/ulanding.cpp
@@ -277,7 +277,7 @@ Radar::init()
 		ds_report.orientation = _rotation;
 		ds_report.id = 0;
 		ds_report.current_distance = -1.0f;	// make evident that this range sample is invalid
-		ds_report.covariance = SENS_VARIANCE;
+		ds_report.variance = SENS_VARIANCE;
 
 		_distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report,
 					 &_orb_class_instance, ORB_PRIO_HIGH);
@@ -463,7 +463,7 @@ Radar::task_main()
 							  report.current_distance;
 				report.min_distance = ULANDING_MIN_DISTANCE;
 				report.max_distance = ULANDING_MAX_DISTANCE;
-				report.covariance = SENS_VARIANCE;
+				report.variance = SENS_VARIANCE;
 				report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_RADAR;
 				report.id = 0;
 
diff --git a/src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp b/src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp
index 332a5503fd..a9fde0422e 100644
--- a/src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp
+++ b/src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp
@@ -667,7 +667,7 @@ VL53LXX::collect()
 
 	report.min_distance = VL53LXX_MIN_RANGING_DISTANCE;
 	report.max_distance = VL53LXX_MAX_RANGING_DISTANCE;
-	report.covariance = 0.0f;
+	report.variance = 0.0f;
 	report.signal_quality = -1;
 
 	/* TODO: set proper ID */
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index e2a345a1ce..756d42e102 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -556,7 +556,7 @@ PX4FLOW::collect()
 	distance_report.min_distance = PX4FLOW_MIN_DISTANCE;
 	distance_report.max_distance = PX4FLOW_MAX_DISTANCE;
 	distance_report.current_distance = report.ground_distance_m;
-	distance_report.covariance = 0.0f;
+	distance_report.variance = 0.0f;
 	distance_report.signal_quality = -1;
 	distance_report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND;
 	/* TODO: the ID needs to be properly set */
diff --git a/src/modules/local_position_estimator/sensors/lidar.cpp b/src/modules/local_position_estimator/sensors/lidar.cpp
index a1478bde25..0f1a3dafc6 100644
--- a/src/modules/local_position_estimator/sensors/lidar.cpp
+++ b/src/modules/local_position_estimator/sensors/lidar.cpp
@@ -77,7 +77,7 @@ void BlockLocalPositionEstimator::lidarCorrect()
 	// use parameter covariance unless sensor provides reasonable value
 	SquareMatrix<float, n_y_lidar> R;
 	R.setZero();
-	float cov = _sub_lidar->get().covariance;
+	float cov = _sub_lidar->get().variance;
 
 	if (cov < 1.0e-3f) {
 		R(0, 0) = _lidar_z_stddev.get() * _lidar_z_stddev.get();
diff --git a/src/modules/local_position_estimator/sensors/sonar.cpp b/src/modules/local_position_estimator/sensors/sonar.cpp
index 79c46f72e1..6071853bad 100644
--- a/src/modules/local_position_estimator/sensors/sonar.cpp
+++ b/src/modules/local_position_estimator/sensors/sonar.cpp
@@ -86,7 +86,7 @@ void BlockLocalPositionEstimator::sonarCorrect()
 	    && !(_sensorTimeout & SENSOR_LIDAR)) { return; }
 
 	// calculate covariance
-	float cov = _sub_sonar->get().covariance;
+	float cov = _sub_sonar->get().variance;
 
 	if (cov < 1.0e-3f) {
 		// use sensor value if reasoanble
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 0b78ca422d..6744841cb4 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -4195,7 +4195,7 @@ protected:
 			msg.min_distance = dist_sensor.min_distance * 100.0f; /* m to cm */
 			msg.max_distance = dist_sensor.max_distance * 100.0f; /* m to cm */
 			msg.current_distance = dist_sensor.current_distance * 100.0f; /* m to cm */
-			msg.covariance = dist_sensor.covariance * 1e4f; // m^2 to cm^2
+			msg.covariance = dist_sensor.variance * 1e4f; // m^2 to cm^2
 
 			mavlink_msg_distance_sensor_send_struct(_mavlink->get_channel(), &msg);
 
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 8b9a88e663..63933fafeb 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -683,7 +683,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
 		d.type = 1;
 		d.id = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND;
 		d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
-		d.covariance = 0.0;
+		d.variance = 0.0;
 
 		if (_flow_distance_sensor_pub == nullptr) {
 			_flow_distance_sensor_pub = orb_advertise_multi(ORB_ID(distance_sensor), &d,
@@ -736,7 +736,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
 	d.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER;
 	d.id = 0;
 	d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
-	d.covariance = 0.0;
+	d.variance = 0.0;
 
 	if (_hil_distance_sensor_pub == nullptr) {
 		_hil_distance_sensor_pub = orb_advertise_multi(ORB_ID(distance_sensor), &d,
@@ -797,7 +797,7 @@ MavlinkReceiver::handle_message_distance_sensor(mavlink_message_t *msg)
 	d.type = dist_sensor.type;
 	d.id = 	MAV_DISTANCE_SENSOR_LASER;
 	d.orientation = dist_sensor.orientation;
-	d.covariance = dist_sensor.covariance * 1e-4f; // cm^2 to m^2
+	d.variance = dist_sensor.covariance * 1e-4f; // cm^2 to m^2
 
 	/// TODO Add sensor rotation according to MAV_SENSOR_ORIENTATION enum
 
diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index ed87153b71..6738e01f56 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -1188,7 +1188,7 @@ int Simulator::publish_distance_topic(mavlink_distance_sensor_t *dist_mavlink)
 	dist.type = dist_mavlink->type;
 	dist.id = dist_mavlink->id;
 	dist.orientation = dist_mavlink->orientation;
-	dist.covariance = dist_mavlink->covariance / 100.0f;
+	dist.variance = dist_mavlink->covariance / 100.0f;
 	dist.signal_quality = -1;
 
 	int dist_multi;
diff --git a/src/platforms/posix/drivers/df_bebop_rangefinder_wrapper/df_bebop_rangefinder_wrapper.cpp b/src/platforms/posix/drivers/df_bebop_rangefinder_wrapper/df_bebop_rangefinder_wrapper.cpp
index 21d96240e6..2ad7bddee3 100644
--- a/src/platforms/posix/drivers/df_bebop_rangefinder_wrapper/df_bebop_rangefinder_wrapper.cpp
+++ b/src/platforms/posix/drivers/df_bebop_rangefinder_wrapper/df_bebop_rangefinder_wrapper.cpp
@@ -160,7 +160,7 @@ int DfBebopRangeFinderWrapper::_publish(struct bebop_range &data)
 
 	distance_data.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
 
-	distance_data.covariance = 1.0f; // TODO set correct value
+	distance_data.variance = 1.0f; // TODO set correct value
 
 	distance_data.signal_quality = -1;
 
diff --git a/src/platforms/posix/drivers/df_isl29501_wrapper/df_isl29501_wrapper.cpp b/src/platforms/posix/drivers/df_isl29501_wrapper/df_isl29501_wrapper.cpp
index 5c29b879e8..1aae077b91 100644
--- a/src/platforms/posix/drivers/df_isl29501_wrapper/df_isl29501_wrapper.cpp
+++ b/src/platforms/posix/drivers/df_isl29501_wrapper/df_isl29501_wrapper.cpp
@@ -167,7 +167,7 @@ int DfISL29501Wrapper::_publish(struct range_sensor_data &data)
 
 	d.id = 0; // TODO set proper ID
 
-	d.covariance = 0.0f;
+	d.variance = 0.0f;
 
 	d.signal_quality = -1;
 
diff --git a/src/platforms/posix/drivers/df_trone_wrapper/df_trone_wrapper.cpp b/src/platforms/posix/drivers/df_trone_wrapper/df_trone_wrapper.cpp
index 61ae5f1279..6f06447486 100644
--- a/src/platforms/posix/drivers/df_trone_wrapper/df_trone_wrapper.cpp
+++ b/src/platforms/posix/drivers/df_trone_wrapper/df_trone_wrapper.cpp
@@ -173,7 +173,7 @@ int DfTROneWrapper::_publish(struct range_sensor_data &data)
 
 	d.orientation = _rotation;
 
-	d.covariance = 0.0f;
+	d.variance = 0.0f;
 
 	d.signal_quality = -1;
 
-- 
GitLab