API review

Proposer: Chad Rockey

Present at review:

  • Tully Foote
  • Eric Perko
  • Gonçalo Cabrita
  • Dave Hershberger
  • Jack O'Quin

Background

There has been a recent flood of low cost environmental sensors. These sensors can provide interesting data with little effort. In fact, these sensors are now appearing in smart phones, tablets, and in breakout boards at sparkfun.com. In order to ensure that this information can be recorded in a standardized way, I'm proposing several new additions to the sensor_msgs package.

I'm basing these messages off of the Android Sensors API. This API will have many developers and many more pieces of hardware. http://developer.android.com/reference/android/hardware/Sensor.html http://developer.android.com/reference/android/hardware/SensorEvent.html

These messages should, without exception, follow REP 103.

Temperature

  • sensor_msgs/Temperature.msg
     # Single temperature reading.
    
     Header header           # timestamp is the time the temperature was measured
                             # frame_id is the location of the temperature reading
    
     float64 temperature     # Measurement of the Temperature in Degrees Celsius
    
     float64 variance        # 0 is interpreted as variance unknown

Temperature Question / concerns / comments

  • (Eric) Why for all of these messages is "0" variance unknown? Why not something like NaN or Inf?

    • (Dave) This would be similar to REP 117. I would think NaN should be chosen 'unknown' since we don't mean to say it is high or low.

    • However the benefit of "0" meaning unknown is that "0" is the default value of all numeric ROS message fields. Therefore the novice thing to do will be the right thing to do: "I don't know what these other fields are about, so I will not set them." 0 is also not ambiguous, because every measurement has some uncertainty, so saying the uncertainty is exactly 0 is clearly not making a factual claim about the measurement.
    • (Chad) Yes, that's right. I chose to leave it as '0'==unknown since that's the convention in the other message like Imu. Also, like Dave mentioned, '0' for variance is just as valid as 'NaN' since it has no physical meaning unless your system lacks randomness. Since these messages are the accumulation of 'random' events (moving air particles + EM fields), I'm confident there will not be a case of '0' variance being valid. :)

    • (Jack) I had the same question, but the rationale for picking 0 makes sense.

Light (Photometric Illuminance)

  • sensor_msgs/Illuminance.msg
     # Single photometric illuminance measurement.  Light should be assumed to be
     # measured along the sensor's x-axis (the area of detection is the y-z plane).
     # The illuminance should have a 0 or positive value and be received with
     # the sensor's +X axis pointing toward the light source.
    
     # Photometric illuminance is the measure of the human eye's sensitivity of the
     # intensity of light encountering or passing through a surface.
    
     # All other Photometric and Radiometric measurements should
     # not use this message.
     # This message cannot represent:
     # Luminous intensity (candela/light source output)
     # Luminance (nits/light output per area)
     # Irradiance (watt/area), etc.
    
     Header header           # timestamp is the time the illuminance was measured
                             # frame_id is the location and direction of the reading
    
     float64 illuminance     # Measurement of the Photometric Illuminance in Lux.
    
     float64 variance        # 0 is interpreted as variance unknown

Illuminance Question / concerns / comments

  • (Dave) The way the comments are worded, it sounds like if the frame has its +X axis pointing out from the sensor's receiver, the illuminance values should all be negative, and if the frame has its -X axis pointing out from the receiver, the illuminance values should be negative.

  • It seems better to restrict the possibilities instead of leaving them open. Let's just pick a coordinate frame convention (+X or -X pointing out from the receiver), and say the illuminance values must always be 0 or positive.
    • (Chad) Good point. I've updated the message to standardize positive values. It looks like luminous flux is different than other flux in that it's a power unit. The simplified usage is more intuitive now (0 is dark, + is more light).

Magnetic Field

  • sensor_msgs/MagneticField.msg
     # Measurement of the Magnetic Field vector at a specific location.
    
     # If the covariance of the measurement is known, it should be filled in
     # (if all you know is the variance of each measurement, e.g. from the datasheet,
     #just put those along the diagonal)
     # A covariance matrix of all zeros will be interpreted as "covariance unknown",
     # and to use the data a covariance will have to be assumed or gotten from some
     # other source
    
    
     Header header                        # timestamp is the time the
                                          # field was measured
                                          # frame_id is the location and orientation
                                          # of the field measurement
    
     geometry_msgs/Vector3 magnetic_field # x, y, and z components of the
                                          # field vector in Tesla
                                          # If your sensor does not output 3 axes,
                                          # put NaNs in the components not reported.
    
     float64[9] magnetic_field_covariance # Row major about x, y, z axes
                                          # 0 is interpreted as variance unknown

Magnetic Field Question / concerns / comments

  • (Dave) How should a user of a 2-axis magnetic compass (for example CMPS03) fill out this message? Should they enter +Inf values in the Z-related covariance matrix elements?

    • (Chad) Two-axis magnetic compasses are typically used in a specially calibrated "differential" mode. This is where the analog signals from the two readings are compared to determine the orientation relative to north given the magnitude and phase in the overall pattern. I don't believe that the sensor you linked can provide measurements in Tesla, so 'compasses' are probably better suited for another message.

    • (Chad) There are some devices that support raw magnetometer mode. We don't run into this problem with the IMU since a single accelerometer/gyro reading is still useful and can be integrated using three-dimensional techniques and not affect the result.

    • (Chad) If one (or more?) of the axes are not supported, that value should just be a NaN. Then it doesn't matter what is in covariance matrix for those values. Does that seem fine?

Fluid Pressure

  • sensor_msgs/FluidPressure.msg
     # Single pressure reading.  This message is appropriate for measuring the
     # pressure inside of a fluid (air, water, etc).  This also includes
     # atmospheric or barometric pressure.
    
     # This message is not appropriate for force/pressure contact sensors.
    
     Header header           # timestamp of the measurement
                             # frame_id is the location of the pressure sensor
    
     float64 fluid_pressure  # Absolute pressure reading in Pascals.
    
     float64 variance        # 0 is interpreted as variance unknown

Fluid Pressure Question / concerns / comments

  • (Dave) Similar concern as with Illuminance message. Here it sounds like a pressure sensor which gets pressed will have a negative "pressure" value. Is that what is intended?

    • (Chad) Yes, that is the intended wording. Much like with accelerometers and gravity, the force is what applies the sign. Just as gravity pulls an object down, the accelerometer measures the acceleration applied to keep an object in place: thus +9.81m/s^2. In this case, if the force is directed into a pressure sensor (like a fingertip sensor), then the directional force is negative, so the resulting pressure (force/area) will be negative.

    • (Chad) I've also added wording clarifying that barometric pressure does not have a direction. My application is for barometric pressure. Force/pressure sensors typically only measure force in one direction and leave pressure ambiguous. If it's confusing to have one message for both, I suggest we scale this message back to fluid pressures only.

    • (Tully) I agree with isolating the types of pressure. They would not be interchangeable and thus warrant a separate message.

Relative Humidity

  • sensor_msgs/RelativeHumidity.msg
     # Single reading from a relative humidity sensor.  Defines the ratio of partial
     # pressure of water vapor to the saturated vapor pressure at a temperature.
    
     Header header             # timestamp of the measurement
                               # frame_id is the location of the humidity sensor
    
     float64 relative_humidity # Expression of the relative humidity
                               # from 0.0 to 1.0.
                               # 0.0 is no partial pressure of water vapor
                               # 1.0 represents partial pressure of saturation
    
     float64 variance          # 0 is interpreted as variance unknown

Relative Humidity Question / concerns / comments

Meeting agenda

To be filled out by proposer based on comments gathered during API review period

Conclusion

Package status change mark change manifest)

  • /!\ Action items that need to be taken.

  • {X} Major issues that need to be resolved


Wiki: sensor_msgs/Reviews/2012-11-16-Low-Cost-Sensor-Roundup_API_Review (last edited 2012-11-19 19:31:36 by ChadRockey)