Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ardupilotmega: update OBSTACLE_DISTANCE_3D message #206

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 5 additions & 6 deletions message_definitions/v1.0/ardupilotmega.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1695,18 +1695,17 @@
<field type="float" name="increment">OSD parameter increment.</field>
</message>
<message id="11037" name="OBSTACLE_DISTANCE_3D">
<wip/>
<!-- This message is work-in-progress and it can therefore change, and should NOT be used in stable production environments -->
Comment on lines -1698 to -1699

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Kind of dubious removing the wip while also adding a field :-)

Fair illustration of where we need a separate message for describing the sensor vs supplying the data.

We really should have

<message id="11037" name="OBSTACLE_SENSOR_3D">
      <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
      <field type="uint8_t" name="sensor_id">Sensor id of the distance sensor.</field>
      <field type="uint8_t" name="sensor_type" enum="MAV_DISTANCE_SENSOR">Class id of the distance sensor type.</field>
      <field type="uint8_t" name="frame" enum="MAV_FRAME">Coordinate frame of reference.</field>
      <field type="uint8_t" name="orientation" enum="MAV_SENSOR_ORIENTATION">Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270</field>
      <field type="float" name="min_distance" units="m">Minimum distance the sensor can measure.</field>
      <field type="float" name="max_distance" units="m">Maximum distance the sensor can measure.</field>
</message>

and then

     <message id="11038" name="OBSTACLE_DISTANCE_3D">
     <description>Obstacle located as a 3D vector.</description>
      <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
      <field type="uint8_t" name="sensor_id">Sensor id of the distance sensor.</field>
      <field type="uint16_t" name="obstacle_id" instance="true">Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.</field>
      <field type="float" name="x" units="m">X position of the obstacle.</field>
      <field type="float" name="y" units="m">Y position of the obstacle.</field>
      <field type="float" name="z" units="m">Z position of the obstacle.</field>
     </message>

We'd be sending 19 bytes of payload rather than 29. Ship has probably sailed on this, however, as there's too much GCS support that would need to be fixed before we get Copter out the door.

<description>Obstacle located as a 3D vector.</description>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
<field type="uint8_t" name="sensor_type" enum="MAV_DISTANCE_SENSOR">Class id of the distance sensor type.</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">Coordinate frame of reference.</field>
<field type="uint16_t" name="obstacle_id" instance="true"> Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.</field>
<field type="float" name="x" units="m"> X position of the obstacle.</field>
<field type="float" name="y" units="m"> Y position of the obstacle.</field>
<field type="float" name="z" units="m"> Z position of the obstacle.</field>
<field type="uint16_t" name="obstacle_id" instance="true">Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.</field>
<field type="float" name="x" units="m">X position of the obstacle.</field>
<field type="float" name="y" units="m">Y position of the obstacle.</field>
<field type="float" name="z" units="m">Z position of the obstacle.</field>
<field type="float" name="min_distance" units="m">Minimum distance the sensor can measure.</field>
<field type="float" name="max_distance" units="m">Maximum distance the sensor can measure.</field>
<field type="uint8_t" name="orientation" enum="MAV_SENSOR_ORIENTATION">Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270</field>

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps this should go up next to MAV_FRAME?

We also need to clarify how orientation interacts with MAV_FRAME. Which is probably, "we ignore all but FRD so orientation is always vs FRD".

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should we specify here which frames we support? isn't that a bit too AP specific? or even AP Version specific?

</message>
</messages>
</mavlink>