autowarefoundation / autoware.universe

https://autowarefoundation.github.io/autoware.universe/
Apache License 2.0
929 stars 609 forks source link

Change vitrual traffic light interface (V2X/V2I) #2703

Open isamu-takagi opened 1 year ago

isamu-takagi commented 1 year ago

Checklist

Description

Currently, communication with infrastructure such as shutter is handled by InfrastructureCommand.msg and VirtualTrafficLightState.msg, but sync issues and requests for cancellation support have been reported. So I propose a new interface to resolve them. Also, since the name is confusing, change it to V2X maneuver coodination, controlled area, or something.

Purpose

Achieve the following use cases.

Possible approaches

Think of a controlled area by a infrastructure as a shared resource. The vehicle acquires and releases locks of that resources. Also, when communicating directly with the infrastructure without using the Internet, it is assumed that the communication area is limited, so lock acquisition and release must be completed within this area.

image

Based on this area, consider the four event points in the table below.

Event Point Description
A. Start point to acquire lock The point to start lock acquisition. If a communication area is defined, this point must be inside it. This point is determined by the vehicle to drive smoothly, but shorter is preferable for sharing locks.
B. Check point to acquire lock The point to wait when the vehicle fails to complete lock acquisition. It must be set so that the vehicle does not enter the controlled area.
C. Start point to release lock The point to start lock release. It must be set so that the vehicle does not enter the controlled area.
D. Check point to release lock The point to wait when the vehicle fails to complete lock release. If a communication area is defined, this point must be inside it, otherwise, this point is not needed.

Entrance and exit

There may be multiple paths within the controlled area, such as intersections. To distinguish between them, the locks are given entrance and exit gate IDs. This is used by the infrastructure to check if a path conflicts. This can also be applied to specifying the number of floors in an elevator.

universe-2703-virtual-traffic-light-lock1

Priority and cancellation

Specifies the lock priority for reassigning locks among multiple vehicles. Typically this is the distance and lower value having higher priority. When reassignment is needed, the infrastructure will request the cancellation to the vehicle. The vehicle will try to release the lock when cancellation is requested.

Architecture

Autoware and facilities communicate using any protocol (if you use a non-standardized protocol, you will need to create a dedicated driver). The V2X component converts ControlledAreaMessages using drivers corresponding to each protocol and relays them to the planning component.

universe-2703-virtual-traffic-light-architecture drawio

Interface

The ManeuverCoodinationMessages does not have a vehicle ID because it is clear that the target vehicle is itself. However, The V2X drivers must provide a vehicle ID when communicating with the facility.

Name Interface Type Data Type
/v2x/maneuver_coodination/command publisher ManeuverCoodinationCommandArray.msg
/v2x/maneuver_coodination/status subscription ManeuverCoodinationStautsArray.msg

ManeuverCoodinationCommand

builtin_interfaces/Time stamp
uint32   command   # command (acquire, release)
string   type      # target facility type
string   id        # target id
string[] path      # entrance and exit id 
uuid     uuid      # Used for synchronization.
float32  priority  # priority hint, distance to intersections, etc.

ManeuverCoodinationStauts

builtin_interfaces/Time stamp
uint32   status    # status (acquired, released, waiting, cancel)
string   type      # target facility type
string   id        # target id
string[] path      # entrance and exit id 
uuid     uuid      # Used for synchronization.

UUID

The UUID is used to prevent the following situations. If messages can be synchronized, a sequence number, etc. is also fine. In the diagram, blue indicates passable and red indicates impassable. It's dangerous if the software thinks it's passable and the facility thinks it's impassable. The facility may allow other vehicles to pass, and multiple vehicles may be passing at the same time.

universe-2703-virtual-traffic-light-uuid

Sequence

universe-2703-virtual-traffic-light-seq1

universe-2703-virtual-traffic-light-seq2

Compatibility with standard messages

ITS Standards

Autoware Signal Request Message Signal Status Message Note
type Not supported Not supported Not necessary if the ID corresponds to the type.
id IntersectionReferenceID IntersectionReferenceID
path IntersectionAccessPoint IntersectionAccessPoint Exit lane is optional.
uuid VehicleID + RequestID VehicleID + RequestID
command Request, Update, Cancellation -
status - unknown, requested, processing, watchOtherTraffic, granted, rejected, maxPresence, reserviceLocked Cancellation is not supported
priority Not supported Not supported RequestorPositionVector can be used.
(vehicle id) VehicleID VehicleID

Lanelet2 format

Controlled area (polygon).

<way id="101">
  <nd ref="5551"/>
  <nd ref="5552"/>
  <nd ref="5553"/>
  <nd ref="5554"/>
  <tag k="type" v="v2x_gate"/>
  <tag k="subtype" v="controlled_area"/>
</way>

Communication area (polygon).

<way id="201">
  <nd ref="6661"/>
  <nd ref="6662"/>
  <nd ref="6663"/>
  <nd ref="6664"/>
  <tag k="type" v="v2x_gate"/>
  <tag k="subtype" v="communication_area"/>
</way>

Start point to acquire/release lock (line). There is no need to define in a map if it can be calculated from the controlled/communication area.

<way id="301">
  <nd ref="7801"/>
  <nd ref="7802"/>
  <tag k="type" v="line_thin"/>
  <tag k="subtype" v="solid"/>
</way>

Check point to acquire/release lock (line). There is no need to define in a map if it can be calculated from the controlled/communication area.

<way id="401">
  <nd ref="7701"/>
  <nd ref="7702"/>
  <tag k="type" v="stop_line"/>
  <tag k="subtype" v="solid"/>
</way>

Infrastructure.

<relation id="1010">
  <member type="way" role="controlled_area" ref="101"/>
  <member type="way" role="communication_area" ref="201"/>
  <member type="way" role="acquire_start" ref="301"/>
  <member type="way" role="acquire_start" ref="302"/>
  <member type="way" role="acquire_check" ref="401"/>
  <member type="way" role="acquire_check" ref="402"/>
  <member type="way" role="release_start" ref="501"/>
  <member type="way" role="release_start" ref="502"/>
  <member type="way" role="release_check" ref="601"/>
  <member type="way" role="release_check" ref="602"/>
  <tag k="type" v="regulatory_element"/>
  <tag k="subtype" v="v2x_gate"/>
  <tag k="category" v="my_category"/>
</relation>

Definition of done

stale[bot] commented 1 year ago

This pull request has been automatically marked as stale because it has not had recent activity.

isamu-takagi commented 9 months ago

The following ideas were commented on in the API WG. https://github.com/orgs/autowarefoundation/discussions/3994

jerry73204 commented 9 months ago

It looks like the areas are fully exclusive. Does it handle the case of ramps where two car flows merge?

isamu-takagi commented 9 months ago

It looks like the areas are fully exclusive. Does it handle the case of ramps where two car flows merge?

I think it is applicable. It can be considered an intersection with two entrances and one exit.

stale[bot] commented 7 months ago

This pull request has been automatically marked as stale because it has not had recent activity.