API review

Proposer: Eric Perko

Reviewers (planning to attend IRC meeting):

  • Chad Rockey
  • Tully Foote
  • Jack O'Quin (not available at IRC conference time)
  • Reviewers needed

Overview

There is a need for a standardized ROS message to represent data from active range sensors other than lasers. Examples of these types of sensors are sonars and simple IR rangers.

Purpose

This new message should represent data from range sensors. These sensors are characterized by a model that emits some form of energy and measures the amount of time it takes that energy emission to return to the sensor in order to calculate distance. Unlike a laser scanner, these sensors do not return the range for a narrow beam; instead, their range reading represents the echo from anywhere along an arc at the distance measured. There are also a number of different types of energy that are commonly used in these sensors - the most common are ultrasound and infrared light.

Proposed Messages

  • sensor_msgs/Range.msg
     # Single range reading from an active ranger that emits energy and reports a
     # distance reading that is valid in an arc.
    
     Header header           # timestamp in the header is the time the ranger
                             # returned the distance reading
    
     uint8 ULTRASOUND=0
     uint8 INFRARED=1
    
     uint8 radiation_type    # the type of radiation used by the sensor
                             # (sound, IR, etc) [enum]
    
     float32 field_of_view   # the size of the arc that the distance reading is
                             # valid for [rad]
                             # the object causing the range reading may have
                             # been anywhere along -field_of_view/2 and
                             # field_of_view/2 at range. 0 angle corresponds
                             # to the x-axis of the sensor.
    
     float32 min_range       # minimum range value [m]
     float32 max_range       # maximum range value [m]
    
     float32 range           # range data [m]
                             # (Note: values < range_min or > range_max
                             # should be discarded)

Question / concerns / comments

Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.

  • (Eric) Should we include a RangeArray message to aggregate Range messages? If they all have separate headers, is there anything to be gained by aggregating them in a message vs. just broadcasting all of them on the same topic? If we want a RangeArray, perhaps we need both Range and RangeStamped messages?

    • (kwc) What is the goal of a RangeArray message? (i.e. convenience or efficiency?) A RangeArray, where each has a separate Header, is fairly expensive performance-wise. Header is variable length because of the string frame_id. Probably less expensive than reading N messages separately, but something to consider.

    • (Tully) I don't think that there are any ranger arrays which are standard enough to justify a RangeArray w/o individual frame_ids. Thus it would have to have to be a RangeStampedArray

      • (Eric) The reason for the RangeArray would mainly be convenience in my opinion. At least the p2os_driver and Goncalo had some sort of array type of message, which is why I wondered if it was useful. However, I do agree with Tully that we pretty much have to have individual frame_ids, as there really aren't standard sensor arrays that this message is for. Since each should be stamped individually, is there any need to include an array message right now? It could be added in the future if people needed it.

      • (Goncalo) We used a RangeArray msg out of convenience since the code we already had was using the range data in the form of an array. For a ROS release a Range msg like the one proposed is perfectly adequate. Furthermore, multiple types of msgs for outputting the same information (various Ranges or a single RangeArray) would make life harder for the people programming the algorithms.

  • (Eric) Should we include the radiation type in the message?

    • (Tully) This is tough, in the normal navigation setting these ranges can usually be reasoned about the same way. However if you are trying to do the advanced processing for things like glass objects you will need the information. The other option is to use topic names to separate the information. The advantage of separate topics w/o the flag is that non of the intermediate nodes need to be aware of the flag. But the cost of passing a uint8 through is pretty low. I'd lean toward keeping it in as proposed.

      • (Eric) Navigation is actually the exact reason I think the radiation type would be helpful. For example, when attempting to generate a costmap for obstacle avoidance, I would not want my laser scanner to be able to clear my sonar sensors if I expect to be navigating in an environment with a lot of glass. If the radiation type is encoded in the message, a costmap node could potentially include the smarts to use both sensors to get the best guess at the environment. I lean away from encoding that information with a topic name, as topics are easily and often remapped to fit the desired inputs/outputs of a given processing node - I wouldn't want to lose information just because some simple filtering node required a ranger topic instead of a sonar or ir topic.

    • (joq) I agree. That information can be useful to some nodes, and is easily ignored by those who don't care. So, the small extra overhead is worthwhile.

  • (Eric) Should we add variance information for the range reading or leave that out of the message?

    • (Tully) How many sensors are there out there which provide accurate variance information? I'm not very familiar with rangers, but if there are good statistics which are used regularly in processing I'd say yes. If it's not common to process the range information with variance I would not suggest overbuilding the message to be future proof.

      • (Eric) I don't see any sensors that actually do have this info, so unless someone knows about a ranger that I don't, we'll leave this out. It looks like the variance on the range information are usually parameters to the processing algorithms (for example, the different values for z_hit, z_max, etc for AMCL). It was also pointed out that this depends not only on the sensor, but on the environment. For example, the variance on a sonar is going to be higher in a crowded space compared to a wide open space with few things to echo off of. There is no way a ranger driver could possibly know that information anyways.

  • (Eric) Is it clear what the scope of this message is? It is not meant to replace the existing LaserScan message.

    • (Tully) I think this is relatively clear, and the distinction can be made explicit in the documentation.

  • (joq) Perhaps a dumb question, but I'll ask anyway: is this device being treated as a planar scan or does the field_of_view arc implicitly apply to both pitch and yaw (in the sensor's frame of reference)?

    • (Eric) Right now, I'm assuming that the field_of_view defines a 3D cone that expands in both pitch and yaw. All of the sonar sensors I've worked with operate in this manner. If there are other rangers that don't have a symmetric field of view, I suppose the field_of_view could be split into two components or something. Is anyone aware of a sensor that actually senses in say, a large horizontal arc but a narrow vertical arc (but still only returns one range reading for the entire arc... not talking about planar laser scanners here)?

      • (Ivan) The Sharp IR sensors that I've used appear to have different vertical and horizontal arcs. The manual recommends mounting the sensor a certain way, because the voltage curve is not well-behaved if the obstacles appear from the wrong direction [1]. Since only one of the fields is valid, I don't think there needs to be 2 FOV's defined in the message. I don't know the sepcifics of how Sonars work.

  • (Ivan) Some IR sensors give a "yes/no" type response, thresholded at a certain value - Sharp GP2D15 for example. Is it worth it to adapt the message to accommodate for these? Perhaps it can be done via an threshold_range field.

    • (Eric) Some sonars do the same thing. We've generally avoided them because we'd much rather have the actual range information than just a yes/no. I'm not sure what a good way to add this into this message would be without having basically two different messages lumped together. I think that the yes/no kind would be better served by it's own message type, as the yes/no type are closer to a "ranged" contact sensor than a ranging sensor in my opinion.

    • (Goncalo) I think this is a very important issue. Many IR sensors also give the amount of light reflected instead of a distance, and even if this provides an idea of distance it cannot be easily translated into meters. The Roomba IR sensors for example output a "yes/no" response plus the amount of light reflected. Perhaps the amount of light reflected could be stored in percentage?

    • * (John) Maybe this needs to be a separate subject but i would like to have the following.


      # Single range reading from an active ranger that emits energy and reports a
      # distance reading that is valid in an arc.
      Header header

    • # timestamp in the header is the time the range
    • # returned the distance reading

    • #Instead of the following
      # uint8 ULTRASOUND=0
      # uint8 INFRARED=1


      #This should provide some very useful info like the ability to map underground pipes(Metal Detector)
      #http://unihedron.com/projects/spectrum/downloads/spectrum_20090210.pdf<<BR>> uint8 Freq # Frequency Used IE. Pulse Induction(Metal Detectors), VLF, UWB, processor should be able to determine what to do with it.
      uint8 Intensity # Used for UAV etc Leave 0 if not used
      uint8 temperature # Used for UAV etc Leave 0 if not used

      # Freq should be able to replace this but it still might be useful
      uint8 radiation_type # the type of radiation used by the sensor
      # (sound, IR, etc) [enum]

      float32 field_of_view # the size of the arc that the distance reading is
      # valid for [rad]
      # the object causing the range reading may have
      # been anywhere along -field_of_view/2 and
      # field_of_view/2 at range. 0 angle corresponds
      # to the x-axis of the sensor.

      float32 min_range # minimum range value [m]
      float32 max_range # maximum range value [m]

      float32 range # range data [m]
      # (Note: values < range_min or > range_max
      # should be discarded)




      I have a VORAD and really need the following but i can't quite figure out how to go about it. Maybe a RADAR sensor_msgs since the rate and targets are only

      seen when moving.
      TargetID ­ The value that distinctly identifies a target. This value has a range of 1 -- 255.
      Rate ­ The target's velocity in MPH. Precision: 0.1 ft/sec (signed)
      Range ­ The target's range in ft. Precision: 0.1 ft Range: 0 -- 6553.5 ft
      Azimuth ­ The target's azimuth in radians. Precision: 0.002 radians (signed)
      TimeStamp ­ Time Stamp of when the data was received.


      VORAD Radar
      http://www.overbot.com/grandchallenge/vbox.html<<BR>>UWB Radar
      https://www.mikrocontroller.net/attachment/27468/osee.pdf<<BR>>Therminvision<<BR>>http://thereminvision.com/version-2/ThereminVision-II-manual.pdf<<BR>>

      • (Eric) I did think about using the frequency instead of just an enum for the type of radiation. However, you'll still need a field to mark the radiation as EM or physical (IR vs sound, for example). Also, do we want to push the burden of deciding which logical radiation bands the sensor is in off to the processing nodes (the just include freq plan) or have a few defined and then force the driver to pick which of the defined bands we fall into (by only having enums available for the radiation type)?

      • (Eric) What is the purpose of the temperature field? Also, are there rangers that report intensity and range at the same time? I'm hesitant to add it if the only purpose intensity serves is to calculate the range (the above mentioned IR sensors are like this)

      • (John) Yea i was thinking that enum would be much easier to process. Useing IR the intensisty to determine range is really more correct. My thought on intensity is that it could be used for line following robots useing color sensors or to keep a lawnmowing type robot in the yard by using a buried invisible dog fence. The buried fence could also be used in a factory floor. The temperature field is used for long range sonar for UAV, thought it would make a nice edition for that group to use. At some point it all starts getting to complicated but these additions would allow alot of flexibility. I guess if a really good list of radiation types could be decided on that should work. Then ultrasound=0 and infrared=1 shouldn't be needed. Metal Detectors could use range(time) and intensity(type of metal) which would be really nice for those that are into gold prospecting etc..

        • (Eric) Unless the color sensors or buried fence sensors are actually outputting a range, they would be much more appropriate in a different message type.

        • (Eric) Would the temperature field be useful for anything beyond correcting the range estimate? For example, would an obstacle map receiving range information care? If it's really only there to compensate for variations in the sensor, it would probably be best to keep it internal to the sensor driver itself. If on the other hand it is useful in some way that I am not aware of when actually interpreting a correct range reading, we could think about including it.

      • * (John) radiation_type

      • 0=?Special Purpose maybe pulse
        1=ULF
        2=ELF
        3=VLF
        4=Long Wave Radio
        5=LF
        6=Ulrasound
        7=MF
        8=Short Wave Rdio
        9=HF
        10=VHF
        11-UHF
        12=Wifi
        13=SHF
        14=EHF
        15=Microwave mm-Band
        16=Terahertz
        17=Far-Infrared
        18=Thermal-Infrared
        19=Near-Infrared
        20=Visible
        21=Ultraviolet
        22=X-Rays
        23=Gamma-Rays
        24-249=???
        250=User1
        251=User2
        252=User3
        253=User4
        254=User5
        255=User6

        • (Eric) I agree that there are a large number of possible radiation types, but I'm generally against adding more types than we have users for right now. Perhaps Tully can comment on the correctness of this, but my opinion is that if we do decide on a radiation type enum, it would be relatively easy to add another value to the enum at anytime without breaking existing clients. I'd rather not have a bazillion radiation types listed a priori, only to find that people really only use 3 or 4.

      • (John) Sorry for the spamming but i forgot to mention using the intensity and a cantenna for a type of wifi radar. This would be very useful for a robot to find its way back to a known good wifi connection. Range would be set to 0 so the processor could detemine location and distance on its own.

        • (Eric) Thing is... the point of this message is that something has already figured out the range information and is passing that to algorithms that are sensor agnostic. Also, since this message is explicitly supposed to contain range information, setting range to 0 and letting something else figure out the range seems to be going against the purpose of the Range message. If you aren't sending a range, why send a Range message in the first place?

        • (John) I guess i just want to do more than it really needs to be for 99% of the time. Would a better approach be to have a "intensity" topic? That should work with color sensors, IR, wifi, metal detecting and so on. I just imagine it being very useful to have TF finding the location and distance to a particular intensity of what ever you want to measure. I think it would be awesome to have a pan-tilt scan around and build up a map of wifi spots or thermal map. Am i missing something cause i'm not finding anything like this in the docs.

Meeting agenda

The review meeting will be held on-line via IRC using #meeting.ros.org at freenode.net.

This meeting has been scheduled for Monday, 2010-10-11 at 4:15PM Eastern Time (1:15PM Pacific Time).

Meeting Transcript ReviewMeetingLog.html

References

[1] http://www.gecad.isep.ipp.pt/iscies09/Papers/19November/iscies09_sharp_model.pdf

Conclusion

Action items:

  • /!\ Make the scope of the message very clear in the message documentation

  • /!\ Create ticket with final message for Tully to include in sensor_msgs

The review period is now over. See https://code.ros.org/trac/ros-pkg/ticket/4488 for the ticket and final version of the message.


Wiki: sensor_msgs/Reviews/2010-10-04_Ranger_Proposal_API_Review (last edited 2010-10-13 20:14:42 by EricPerko)