WO2023079690A1 - Control device, traffic rectification system, control method, and program - Google Patents

Control device, traffic rectification system, control method, and program Download PDF

Info

Publication number
WO2023079690A1
WO2023079690A1 PCT/JP2021/040810 JP2021040810W WO2023079690A1 WO 2023079690 A1 WO2023079690 A1 WO 2023079690A1 JP 2021040810 W JP2021040810 W JP 2021040810W WO 2023079690 A1 WO2023079690 A1 WO 2023079690A1
Authority
WO
WIPO (PCT)
Prior art keywords
state
control device
dynamics
vehicle
traffic
Prior art date
Application number
PCT/JP2021/040810
Other languages
French (fr)
Japanese (ja)
Inventor
健太 丹羽
修功 上田
宏 澤田
昭典 藤野
Original Assignee
日本電信電話株式会社
Priority date (The priority date is an assumption and is not a legal conclusion. Google has not performed a legal analysis and makes no representation as to the accuracy of the date listed.)
Filing date
Publication date
Application filed by 日本電信電話株式会社 filed Critical 日本電信電話株式会社
Priority to PCT/JP2021/040810 priority Critical patent/WO2023079690A1/en
Priority to JP2023557546A priority patent/JPWO2023079690A1/ja
Publication of WO2023079690A1 publication Critical patent/WO2023079690A1/en

Links

Images

Classifications

    • GPHYSICS
    • G08SIGNALLING
    • G08GTRAFFIC CONTROL SYSTEMS
    • G08G1/00Traffic control systems for road vehicles
    • G08G1/16Anti-collision systems

Definitions

  • the present invention relates to technology for autonomously rectifying traffic (which may also be referred to as traffic control) by multiple vehicles.
  • the present invention has been made in view of the above points, and aims to provide technology for realizing traffic rectification without using traffic lights by autonomously controlling each vehicle.
  • the control in a traffic control system includes a plurality of mobile bodies equipped with a control device, and the plurality of mobile bodies autonomously rectifies traffic so as to prevent collisions between the mobile bodies.
  • a device Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile.
  • a state updating unit that updates the state of the moving object under constraints for deterring collisions; an output unit that outputs the state updated by the state update unit and a message;
  • a controller is provided comprising:
  • a technology for realizing traffic rectification without using traffic lights by autonomously controlling each vehicle.
  • FIG. 3 shows a NODE-based DNN architecture
  • Fig. 3 shows an extended NODE-based DNN architecture following a state-space model
  • Fig. 3 shows a NOS-based DNN architecture
  • FIG. 1 illustrates Algorithm 1
  • FIG. 4 is a diagram showing representative parameters; It is a figure for demonstrating an experiment. It is a figure for demonstrating an experiment.
  • FIG. 2 is a diagram showing an example of the functional configuration of the vehicle 1;
  • FIG. 2 is a diagram showing a functional configuration of a control device 100;
  • FIG. 3 is a diagram showing a functional configuration of a control server 200;
  • FIG. It is a figure which shows the hardware configuration example of an apparatus.
  • FIG. 1 shows a configuration example of a traffic control system according to this embodiment.
  • the traffic straightening system has a plurality of nodes, and each node wirelessly communicates with other nearby nodes. Connections between nodes (connections for wireless communication) are called edges.
  • this traffic control system for example, vehicles can move without collisions.
  • a node is not limited to a specific object, but in this embodiment, it is assumed that a node is a vehicle traveling on a road. In the following, a node may also be referred to as a "vehicle”. A node may also be called a "moving object”.
  • Figure 2 shows an image of multiple vehicles running on the road.
  • Each vehicle performs autonomous speed control so as not to collide with other vehicles and approach a target speed, based on communication with nearby vehicles and state updates by a DNN (deep neural network). running.
  • a DNN deep neural network
  • speed is used as the state, but this is an example. It is also possible to use states other than velocity, or both velocity and non-velocity. Other states than speed include, for example, route, lane, and steering direction.
  • the neural network model installed in each vehicle is a model for solving the initial value problem of ordinary differential equations expressing state update dynamics.
  • the ordinary differential equation can be expressed, for example, as follows.
  • M1 corresponds to in-vehicle state updates
  • M2 corresponds to near vehicle-to-vehicle communication (message passing).
  • the state (x) is updated according to the dynamics (M 1 +M 2 ) under the constraint of collision avoidance (Ax+b ⁇ 0).
  • M1 and M2 A detailed example of M1 and M2 will be described later.
  • an ordinary differential equation is discretized to form a control algorithm (neural network) that alternately repeats (1) vehicle internal state update and (2) vehicle-to-vehicle communication.
  • Fig. 3 shows an image of the above control algorithm when the number of vehicles is N.
  • the in-vehicle state update in each vehicle and the communication between each vehicle's neighboring vehicles are alternately repeated.
  • the overall computation is distributed and parallelized, so the computation on each vehicle is lightweight.
  • inter-vehicle communication is close proximity sparse communication that does not put pressure on the NW band.
  • the adjoint method is used for the neural network learning (learning the parameter ⁇ ) that updates the state as described above. That is, efficient differential calculation is performed by back propagation calculation of a neural network based on the adjoint method, and the parameter ( ⁇ ) is learned so as to accelerate the average speed toward the target speed under the constraint of collision prevention.
  • the parameter ( ⁇ ) is common to all vehicles, but it is also possible to learn so that each vehicle uses a different parameter ⁇ .
  • FIG. 4 is a diagram more specifically showing the system when the node is a vehicle.
  • the control device 100 has the DNN model described above, and performs state acquisition, state update, and state output.
  • a control server 200 is provided.
  • the control server 200 receives information such as the state from each vehicle (may be the cost calculated by each vehicle), learns the parameter ( ⁇ ), and transmits the learned parameter ⁇ to each vehicle. .
  • control server 200 The provision of the control server 200 is an example. Each vehicle may learn the parameter ⁇ by itself without the control server 200 .
  • NODE Neural Ordinary Differential Equation
  • IVPs Initial Value Problems
  • FIG. 5 shows a NODE-based DNN architecture. As shown in FIG. 5, the states are updated sequentially and the cost is calculated based on each state.
  • an external control input o(t) is further introduced, which NODE does not have.
  • IVP can be defined by the following equation (1).
  • NODE-based DNN architecture can be constructed as a basic IVP discretization
  • different discretization methods in ODE solvers such as higher-order Runge-Kutta solvers, construct different NODE-based DNN architectures. available for
  • NODE allows us to handle basic IVPs, its application to large-scale systems with complex dynamics M, which can be represented as a graph consisting of many subsystems (nodes) and their connections (edges), is difficult.
  • An example of such a system is the system of vehicles that rectifies traffic as described above.
  • the present embodiment adopts federated dynamics learning using neural operator splitting (NOS) as an extension of NODE.
  • NOS neural operator splitting
  • the overall dynamics M is decomposed into (i) M1 for state transitions of each node and (ii) M2 for message passing between nodes for efficient management of large-scale systems in graph form. and is represented by the following formula (2).
  • M1 can be further decomposed into sub-dynamics at each node.
  • M2 is set to have no learnable parameters as it relates to message passing.
  • the state transition is the residual , recurrent, and alternating forms.
  • state domain relaxation is performed to impose physical constraints. That is, in equation (2), the state domain of M1 and the state domain of M2 are the same as x, but in the NOS of this embodiment, in order to impose physical constraints on the state variables of many nodes, Relax the state domain constraint of equation (2).
  • M2 By designing M2 as 0, some distance is preserved between other vehicles. As a result, it is expected that the parameter search area will be appropriately limited, that, for example, vehicle collisions will be prevented, and that .theta. will be learned quickly and stably.
  • NOS is associated with a constrained cost minimization problem derived by the ADMM method (Alternating Direction Method of Multipliers).
  • extended NODE following the state-space model
  • extended NODE is an extended NODE-based DNN architecture following a state-space model assuming a noisy, nonlinear, and indirect observation process for the state variable x in real applications.
  • R(t) is the covariance matrix of the measurement noise ⁇
  • T represents the transpose of the matrix.
  • the measurement noise follows a Gaussian distribution ⁇ ⁇ Norm(0, ⁇ 2 )
  • J(x, ⁇ ) for learning ⁇ is given by equation (5) below: given by the constrained cost integral minimization problem.
  • H in equation (4) is the identity operator, as assumed in NODE.
  • the learning of ⁇ for the optimal dynamics model M is performed by alternately/repeatingly performing successive forward propagation (3) and successive backward propagation (7) using g done.
  • the forward Euler method (8), backward Euler method (9), and Crank-Nicholson method (second-order Runge-Kutta) shown below can be used to approximate differential equations with discrete state transition rules.
  • the NODE-based DNN architecture can be used for recursive stacks of K iterations based on residual state updates ((8), (9), or (10)) as shown in FIGS. be.
  • the forward Euler method can be regarded as a ResNet.
  • the adjoint method can be used to calculate the gradient in learning ⁇ .
  • the NODE-based DNN architecture is extended to follow FIG. 6 by discretizing the continuous backward propagation (7), as shown in equation (11) below.
  • a NOS-based DNN architecture for federated dynamics learning is introduced, and traffic rectification is achieved by alternately performing vehicle state updating (i) and message passing (ii) between vehicles. I am trying to solve the problem.
  • NOS Neurological operator decomposition
  • PRS and DRS are selected among these. Because they are based on the Crank-Nicholson method (10) with second-order accuracy, both are expected to achieve accurate state transitions.
  • PRS-Net and DRS-Net are shown in FIG. From equations (12) and (13), PRS-Net and DRS-Net differ in that DRS-Net uses an averaging operation of twice the step size. Learning of ⁇ in NOS (PRS-Net, DRS-Net, etc.) can be performed according to the adjoint method described above.
  • ADMM flow it takes into account the discrete time limitation to create a continuous ODE form of (discrete) ADMM.
  • ⁇ M 1 , M 2 ⁇ are specified by the (sub)differential of the cost function V minimized with an affine transformation using (A T A) ⁇ 1 .
  • V1 is a smooth but non-convex function
  • V2 is a convex function but may not be differentiable.
  • Equation (14) differs from the ADMM flow in the following ways: (i) the parameter ⁇ in V 1 is learnable and non-convex, (ii) V 2 may not be differentiable One, (iii) a bias b is added for generalization of the transform, (iv) ⁇ A,b ⁇ can be time-varying.
  • Equation (14) we relate it to the constrained cost minimization problem.
  • ⁇ V 1 , V 2 ⁇ we constrain ⁇ V 1 , V 2 ⁇ to be convex and make the constraint parameters ⁇ A, b ⁇ time-invariant.
  • equation (15) A linearly constrained convex minimization problem is given by the following equation (15).
  • Equation (16) Equation (16) below.
  • V 1 in equation (14) can be non-convex, but if ⁇ t is small enough, it can be Taylor expanded around the previous state x k ⁇ 1 as in equation (17) below can be approximated by a local quadratic form.
  • G(t) consists of a set N(t) of N(t) nodes and a set E(t) of E(t) edges.
  • E i (t) ⁇ j ⁇ N(t)
  • control input o i includes the edge information E i and the time-varying constraint parameters ⁇ A i
  • j ⁇ is associated with ⁇ A,b ⁇ in equation (14) as follows.
  • Equation (18) For federated dynamics learning, a cost function for state transition is formulated as shown in Equation (18) below.
  • V local,i is designed to accelerate the velocity state towards the target
  • inequality constraints are designed to maintain inter-vehicle distance Designed.
  • Equation (18) Equation (19) below.
  • the indicator function is expressed as Equation (20) below.
  • the cost function (21) having the quadratic approximation (17) is substituted into the dynamics (14) in PRS-Net (12) and DRS-Net (13), so that federated dynamics learning A NOS-based DNN architecture for is defined.
  • Each vehicle autonomously updates its state (eg, speed) using external control inputs (eg, inputs from cameras/LiDAR) and message passing between nearby vehicles.
  • state e.g, speed
  • external control inputs e.g, inputs from cameras/LiDAR
  • the behavior of the distributed control system is a function of state transition dynamics, and the inputs are the previous state x and the control input o. Also, NOS-based federated dynamics learning is used to optimize the parameter ⁇ of the state transition dynamics.
  • This technology describes using an ADMM to set each vehicle to a target speed while maintaining a certain distance between vehicles.
  • problems (i) extra link nodes are needed to connect vehicle nodes; (ii) there are no learnable parameters in the state transition dynamics.
  • the technology according to the present embodiment (i) realizes completely decentralized traffic rectification consisting only of vehicle nodes, and (ii) realizes federated dynamics learning for obtaining optimal autonomous state transition dynamics. are doing.
  • a bar at the beginning of the character is indicated in front of the character, such as “ - ⁇ ”.
  • the goal of federated dynamics learning for decentralized signal-free traffic rectification is to keep x i (t) close to the target x tar ⁇ [0,1] while keeping some distance between vehicles to avoid collisions. Na- is to find ⁇ .
  • Equation (4) the following function is selected as the cost function in Equation (4).
  • Each vehicle runs in the center of a single-lane road and overtaking is prohibited. That is, each vehicle follows the other vehicle across the intersection.
  • the control inputs o i of each vehicle are the normalized velocity o spd,i , the 2D direction vector o dir,i , the 2D position vector o pos,i , the surrounding image o img,i of each vehicle, the mapping vector o map, i
  • j is for converting the 2D positions into scalar values for measuring the distance from the i th vehicle to the j th vehicle.
  • the quadratic function is the learnable acceleration
  • This term uses ⁇ (0,1) to approximate x i (t) to the point between x tar and the previous state x i,k ⁇ 1 as follows: be.
  • the value range limit for x i is x i ⁇ [0,1].
  • differs between PRS-NET and DRS-NET. Also, [ ] ⁇ [0, 1] indicates that the internal element value is clamped to the range between 0 and 1,
  • i ⁇ are chosen to make the left hand side of equation (23) positive.
  • ⁇ A, b ⁇ cannot be uniquely determined because there is ambiguity when converting equation (23) into the form of the inequality constraint Ax+b ⁇ 0 shown in equation (18).
  • ⁇ A,b ⁇ is associated with each vehicle's acceleration/deceleration. For example, when A i
  • a front flag/rear (back) flag to prevent the vehicle in front from braking as much as possible.
  • j ⁇ in this embodiment is as shown in Equation (24) below.
  • Equation (25) above corresponds to equation (23).
  • equation (23) From the update rule for x in equation (22), it can be seen that vehicle i brakes when A i
  • j ⁇ is to avoid collisions by adjusting the acceleration/deceleration of the vehicle behind after assigning a front/rear flag to each vehicle pair. is.
  • the front/rear allocation is determined by the position and orientation of the vehicle pair.
  • the current speed and position can be used to determine the assignment of the front/back flag with the estimated remaining time to the center of the intersection.
  • equation (23) is to accelerate/decelerate the trailing vehicle as shown in equation (24). is done by normalizing A i
  • Algorithm 1 Alg.1
  • Algorithm 1 Algorithm 1
  • each node i performs control input, edge connection, and acquisition of parameters ⁇ A i
  • each node i performs message passing (receiving message z j
  • each node updates its internal state based on equation (22). This allows node i to compute k+1 velocities (x i ) and k+1 messages (z i
  • Each vehicle (or control server 200) performs backward propagation (11) by using the recorded data ⁇ x, o, A, b ⁇ to update ⁇ .
  • Federated dynamics learning is performed by iterative I-rounds of forward-propagation/back-propagation.
  • FIG. 7 shows an image in which the control server 200 records data ⁇ x, o, A, b ⁇ at each discrete time and performs backward propagation parameter learning based on cost calculation. ing.
  • N 30 vehicles were randomly placed in the traffic simulator.
  • 10 road maps were prepared. To avoid overfitting to the training data, each road map has small random perturbations for straight road lengths and intersection locations.
  • An image o img,i of each vehicle and its surroundings was generated at each discrete time instant as the control input for determining the acceleration/deceleration of each vehicle.
  • the size of the image is defined as 64 (W) x 64 (H) x 5 (Ch).
  • Each channel consists of (1) the surrounding roads, (2) the surrounding vehicle positions, (3) their normalized velocities, and (4,5) the 2D direction vectors of the surrounding vehicles.
  • Each image is rotated so that each vehicle is facing the same direction. Examples of o img for vehicle 1 and vehicle 30 in FIG. 10 are shown in FIGS. 11 and 12, respectively.
  • FIG. 13 shows an image of repeating state update and learning for each round.
  • PRS-Net and DRS-Net are set to Alg. 1.
  • PRS-Net and DRS-Net are set to Alg. 1.
  • PnP-Net uses state transitions implemented in recursive DNNs for updating x. The method avoided analytical derivation as much as possible and learned in a data-driven manner. The DNN parameter sizes of this PnP-Net were initially set as close as possible to the NOS parameter values.
  • both PnP-Net and learning-impossible NOS alternately perform (i) internal state update and (ii) message passing between adjacent vehicles.
  • FIG. 14 shows the experimental results.
  • FIG. 14 shows that the average normalized speed changes with increasing number of rounds.
  • the performance difference between them is small. That is, both methods are effective for NOS-based associative dynamics learning.
  • - ⁇ was updated to maintain the inter-vehicle distance as much as possible.
  • the average normalized speed is 0.30 for non-learnable PRS-Net and 0 for non-learnable DRS-Net. .31, and 0.56 with SUMO's native traffic control system.
  • Experimental results show that NOS-based associative dynamics learning is effective.
  • FIG. 15 is a diagram that more clearly shows the difference between NOS-based joint dynamics learning (proposed method) and the conventional method of SUMO implementation (conventional method). As shown in FIG. 15, in the proposed method, the normalization speed approaches the target value as learning progresses, and the speed is greatly improved over the conventional method (SUMO implementation).
  • FIG. 16 shows a convergence curve for the evaluation set, showing better performance as it approaches 0.0.
  • the loss value proportional to the difference between the normalized speed target value and the current value decreases with learning.
  • FIG. 17 shows a configuration example of the vehicle 1.
  • the vehicle 1 has a camera 11, a sensor 12, a control device 100, a communication section 13, and a drive section .
  • Camera 11 acquires an image of the surroundings.
  • the sensor 12 acquires its own position information by Lidar, GPS, or the like, for example.
  • Sensor 12 may include the ability to acquire its own velocity. Also, a sensor that further acquires information other than these may be mounted.
  • the control device 100 inputs external information acquired by the camera 11 and the sensor 12, performs the processing of Algorithm 1, and outputs the state (speed) x and the message z.
  • the control device 100 may also include a function of parameter learning by backward propagation based on Equation (11).
  • the communication unit 13 receives a message transmitted from another adjacent vehicle, passes the message to the control device 100, and transmits a message output from the control device 100 to the other adjacent vehicle. In addition, when learning is performed by the control server 200, the communication unit 13 transmits the recorded data ⁇ x, o, A, b ⁇ obtained in the state update to the control server 200, and the latest learned parameter ⁇ Received from control server 200 .
  • the drive unit 14 includes a function (engine, motor, etc.) for running according to the state x output from the control device 100 . For example, when a certain speed is output as a state from the control device 100, the vehicle is driven so as to run at that speed.
  • a function engine, motor, etc.
  • FIG. 18 shows a configuration example of the control device 100.
  • the control device 100 includes an input section 110 , a state update section 120 , an output section 130 , a data storage section 140 and a learning section 150 . Note that when learning is performed by the control server 200 , the learning unit 150 may not be provided in the control device 100 .
  • the input unit 110 inputs external information o acquired by the camera 11 and the sensor 12 and a message z received from an adjacent vehicle.
  • the state update unit 120 is a DNN that implements a NOS that updates the states of x and z according to Algorithm 1 .
  • the output unit 130 outputs the state x obtained by the state update unit 120 and the message z.
  • the data storage unit 140 records the data ⁇ x, o, A, b ⁇ obtained in the process of processing by the state update unit 120 for each discrete time. Further, the data storage unit 140 stores the latest learned parameter ⁇ , and the state update unit 120 executes state update processing using the latest learned parameter ⁇ .
  • the learning unit 150 learns the parameter ⁇ by backward propagation (11) using the recorded data ⁇ x, o, A, b ⁇ , and stores the learned parameter ⁇ in the data storage unit 140.
  • FIG. 19 shows a configuration example of the control server 200.
  • the control server 200 includes an input unit 210, a learning unit 220, an output unit 230, and a data storage unit 240.
  • the input unit 210 receives recorded data ⁇ x, o, A, b ⁇ from each vehicle.
  • the data storage unit 240 stores recorded data ⁇ x, o, A, b ⁇ received from each vehicle.
  • the learning unit 220 learns the parameter ⁇ by backward propagation (11) using the recorded data ⁇ x, o, A, b ⁇ stored in the data storage unit 240 .
  • the output unit 230 transmits the learned parameter ⁇ to each vehicle.
  • Both the control device 100 and the control server 200 can be realized, for example, by causing a computer to execute a program.
  • the device can be realized by executing a program corresponding to the processing performed by the device using hardware resources such as a CPU, GPU, and memory built into the computer.
  • the above program can be recorded in a computer-readable recording medium (portable memory, etc.), saved, or distributed. It is also possible to provide the above program through a network such as the Internet or e-mail.
  • FIG. 20 is a diagram showing a hardware configuration example of the computer.
  • the computer of FIG. 20 has a drive device 1000, an auxiliary storage device 1002, a memory device 1003, a processor 1004, an interface device 1005, a display device 1006, an input device 1007, an output device 1008, etc., which are interconnected by a bus BS.
  • the processor 1004 may be a CPU, a GPU, or both a CPU and a GPU.
  • a program that implements the processing in the computer is provided by a recording medium 1001 such as a CD-ROM or memory card, for example.
  • a recording medium 1001 such as a CD-ROM or memory card
  • the program is installed from the recording medium 1001 to the auxiliary storage device 1002 via the drive device 1000 .
  • the program does not necessarily need to be installed from the recording medium 1001, and may be downloaded from another computer via the network.
  • the auxiliary storage device 1002 stores installed programs, as well as necessary files and data.
  • the memory device 1003 reads and stores the program from the auxiliary storage device 1002 when a program activation instruction is received.
  • the processor 1004 implements the functions of the light touch maintaining device 100 according to programs stored in the memory device 1003 .
  • the interface device 1005 is used as an interface for connecting to a network or the like.
  • a display device 1006 displays a GUI (Graphical User Interface) or the like by a program.
  • An input device 1007 is composed of a keyboard, a mouse, buttons, a touch panel, or the like, and is used to input various operational instructions.
  • the output device 1008 outputs the calculation result.
  • NOS is proposed as an extension of NODE for federated dynamics learning, and the two subdynamics of equation (2) are applied to (i) internal state updating and (ii) message passing. decided to assign.
  • NOS-based DNN architectures such as PRS-Net and DRS-Net through the discretization of equation (2) based on the operator decomposition method.
  • NOS has also been successfully applied to the problem of signal-free traffic rectification with the goal of finding the dynamics parameter - ⁇ that maximizes the average speed to a target value.
  • a control device in a traffic rectification system comprising a plurality of mobile bodies equipped with a control device, wherein the plurality of mobile bodies autonomously rectify traffic so as to prevent collisions between the mobile bodies, Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state updating unit that updates the state of the moving object under constraints for deterring collisions; an output unit that outputs the state updated by the state update unit and a message; A control device comprising: (Section 2) 2.
  • the control device uses a neural network to alternately repeat the state update of the moving object and the message passing.
  • (Section 3) 3.
  • the state update unit calculates the state at the next point in time based on the state at the point in time, the external control input at the point in time, and the message received from another mobile object at the point in time. 4.
  • the control device according to any one of items 3 to 3. (Section 5) 5.
  • the control device wherein the restriction is to set the distance between the mobile body and the other mobile body to a predetermined distance or more, which is calculated based on the external control input.
  • (Section 6) a plurality of mobile bodies equipped with the control device according to any one of items 1 to 5; a control server that updates the parameters of the neural network provided in the state update unit by back propagation calculation based on the adjoint method so that the average speed of a plurality of moving bodies approaches a target speed under the constraints. .
  • (Section 7) A control method executed by a control device in a traffic control system comprising a plurality of mobile bodies equipped with a control device and autonomously controlling traffic so as to prevent collisions between the mobile bodies.
  • a control method comprising: (Section 8) A program for causing a computer to function as each unit in the control device according to any one of items 1 to 5.

Landscapes

  • Physics & Mathematics (AREA)
  • General Physics & Mathematics (AREA)
  • Traffic Control Systems (AREA)

Abstract

A control device provided in each of a plurality of moving bodies that are provided in a traffic rectification system wherein the plurality of moving bodies autonomously perform traffic rectification to prevent collisions between these moving bodies, said control device being provided with: a state update unit that updates the states of the moving bodies under constraints for preventing collisions between the moving bodies, on the basis of state update dynamics including sub-dynamics for updating the states of the moving bodies, and sub-dynamics for message passing between each moving body and other moving bodies in proximity; and an output unit that outputs the states updated by the state update unit and a message.

Description

制御装置、交通整流システム、制御方法、及びプログラムControl device, traffic rectification system, control method, and program
 本発明は、複数の車両により自律的に交通整流(交通制御と称してもよい)を行う技術に関連するものである。 The present invention relates to technology for autonomously rectifying traffic (which may also be referred to as traffic control) by multiple vehicles.
 従来技術において、道路の各交差点等に設置された信号機により、車両が衝突することなく安全に走行するための交通整流が行われている。しかし、従来技術では、信号待ちによる頻繁な停止や、合流や右左折に伴う一時停止などによって、都市部では慢性的な渋滞が発生してしまう、という課題があった。 In the conventional technology, traffic signals installed at intersections of roads rectify traffic so that vehicles can travel safely without colliding. However, the conventional technology has the problem that chronic traffic jams occur in urban areas due to frequent stops due to traffic lights, temporary stops due to merging and right/left turns, and the like.
 今後、自律走行車両が普及するにつれて、従来の信号機を用いた集中制御システムから、分散制御システム(信号フリー交通整流)への置き換えが行われ、分散制御システムにより上記の課題を解決していくことが想定される。 In the future, as autonomous vehicles become more widespread, the conventional centralized control system using traffic lights will be replaced with a distributed control system (signal-free traffic rectification), and the above problems will be solved by the distributed control system. is assumed.
 本発明は上記の点に鑑みてなされたものであり、各車両が自律的に制御を行うことにより、信号機を使用しない交通整流を実現するための技術を提供することを目的とする。 The present invention has been made in view of the above points, and aims to provide technology for realizing traffic rectification without using traffic lights by autonomously controlling each vehicle.
 開示の技術によれば、制御装置を備える移動体を複数台備え、当該複数台の移動体が自律的に、移動体間の衝突を抑止するように交通整流を実施する交通整流システムにおける前記制御装置であって、
 前記移動体の状態更新のためのサブダイナミクスと、前記移動体に近接する他の移動体との間で行われるメッセージパッシングのためのサブダイナミクスとを有する状態更新ダイナミクスに基づいて、移動体間の衝突を抑止するための制約下で、前記移動体の状態を更新する状態更新部と、
 前記状態更新部により更新された状態と、メッセージとを出力する出力部と、
 を備える制御装置が提供される。
According to the disclosed technique, the control in a traffic control system includes a plurality of mobile bodies equipped with a control device, and the plurality of mobile bodies autonomously rectifies traffic so as to prevent collisions between the mobile bodies. a device,
Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state updating unit that updates the state of the moving object under constraints for deterring collisions;
an output unit that outputs the state updated by the state update unit and a message;
A controller is provided comprising:
 開示の技術によれば、各車両が自律的に制御を行うことにより、信号機を使用しない交通整流を実現するための技術が提供される。 According to the disclosed technology, a technology is provided for realizing traffic rectification without using traffic lights by autonomously controlling each vehicle.
実施の形態におけるシステム構成例を示す図である。It is a figure which shows the system configuration example in embodiment. 実施の形態の概要を説明するための図である。BRIEF DESCRIPTION OF THE DRAWINGS It is a figure for demonstrating the outline|summary of embodiment. 実施の形態の概要を説明するための図である。BRIEF DESCRIPTION OF THE DRAWINGS It is a figure for demonstrating the outline|summary of embodiment. システム構成例を示す図である。It is a figure which shows the system configuration example. NODEベースのDNNアーキテクチャを示す図である。Fig. 3 shows a NODE-based DNN architecture; 状態空間モデルに従う拡張NODEベースのDNNアーキテクチャを示す図である。Fig. 3 shows an extended NODE-based DNN architecture following a state-space model; NOSベースのDNNアーキテクチャを示す図である。Fig. 3 shows a NOS-based DNN architecture; アルゴリズム1を示す図である。FIG. 1 illustrates Algorithm 1; 代表的なパラメータを示す図である。FIG. 4 is a diagram showing representative parameters; 実験を説明するための図である。It is a figure for demonstrating an experiment. 実験を説明するための図である。It is a figure for demonstrating an experiment. 実験を説明するための図である。It is a figure for demonstrating an experiment. 実験を説明するための図である。It is a figure for demonstrating an experiment. 実験結果を示す図である。It is a figure which shows an experimental result. 実験結果を示す図である。It is a figure which shows an experimental result. 実験結果を示す図である。It is a figure which shows an experimental result. 車両1の機能構成例を示す図である。2 is a diagram showing an example of the functional configuration of the vehicle 1; FIG. 制御装置100の機能構成を示す図である。2 is a diagram showing a functional configuration of a control device 100; FIG. 制御サーバ200の機能構成を示す図である。3 is a diagram showing a functional configuration of a control server 200; FIG. 装置のハードウェア構成例を示す図である。It is a figure which shows the hardware configuration example of an apparatus.
 以下、図面を参照して本発明の実施の形態(本実施の形態)を説明する。以下で説明する実施の形態は一例に過ぎず、本発明が適用される実施の形態は、以下の実施の形態に限られるわけではない。 An embodiment (this embodiment) of the present invention will be described below with reference to the drawings. The embodiments described below are merely examples, and embodiments to which the present invention is applied are not limited to the following embodiments.
 (実施の形態の概要)
 図1に本実施の形態における交通整流システムの構成例を示す。図1に示すように、本交通整流システムは複数のノードを有し、各ノードは近隣の他のノードと無線通信を行う。ノードとノードとの接続(無線通信を行うための接続)をエッジと呼ぶ。本交通整流システムにおいて、例えば車両は衝突しないように移動することができる。
(Overview of Embodiment)
FIG. 1 shows a configuration example of a traffic control system according to this embodiment. As shown in FIG. 1, the traffic straightening system has a plurality of nodes, and each node wirelessly communicates with other nearby nodes. Connections between nodes (connections for wireless communication) are called edges. In this traffic control system, for example, vehicles can move without collisions.
 ノードは特定の物に限定されないが、本実施の形態では、ノードは道路を走行する車両であることを想定している。以下では、ノードを「車両」と呼んでもよい。また、ノードを「移動体」と呼んでもよい。 A node is not limited to a specific object, but in this embodiment, it is assumed that a node is a vehicle traveling on a road. In the following, a node may also be referred to as a "vehicle". A node may also be called a "moving object".
 図2は、複数の車両が道路上を走行するイメージを示している。各車両は、近接車両との間の通信と、DNN(ディープニューラルネットワーク)による状態更新とに基づき、他の車両と衝突せず、かつ、目標の速度に近づくように、速度の自律制御を行って走行している。これにより、交通事故(衝突)を抑止する中で,移動・輸送時間を限界まで短縮することが期待できる。なお、本実施の形態では、状態として速度のみを使用しているが、これは例である。状態として、速度以外のもの、あるいは、速度と速度以外のものの両方を使用することも可能である。速度以外の状態として、例えば、ルート、車線、ステアリング方向などの状態がある。 Figure 2 shows an image of multiple vehicles running on the road. Each vehicle performs autonomous speed control so as not to collide with other vehicles and approach a target speed, based on communication with nearby vehicles and state updates by a DNN (deep neural network). running. As a result, it is expected that travel and transportation time will be shortened to the limit while preventing traffic accidents (collisions). In addition, in this embodiment, only the speed is used as the state, but this is an example. It is also possible to use states other than velocity, or both velocity and non-velocity. Other states than speed include, for example, route, lane, and steering direction.
 各車両が備えるニューラルネットワークのモデルは、状態更新ダイナミクスを表現した常微分方程式の初期値問題を解くためのモデルである。当該常微分方程式は、例えば、下記のように表すことができる。 The neural network model installed in each vehicle is a model for solving the initial value problem of ordinary differential equations expressing state update dynamics. The ordinary differential equation can be expressed, for example, as follows.
 dx/dt=M(x,t,θ,A,b)+M(x,t,A,b)  
 上記のように、状態更新ダイナミクスは、MとMに分解される。Mは、車両内状態更新に対応し、Mは、近接車両間通信(メッセージパッシング)に対応する。
dx/dt=M 1 (x, t, θ, A, b)+M 2 (x, t, A, b)
As above, the state update dynamics are decomposed into M1 and M2 . M1 corresponds to in-vehicle state updates and M2 corresponds to near vehicle-to-vehicle communication (message passing).
 各車両において、状態(x)を衝突抑止の制約(Ax+b≦0)下で、ダイナミクス(M+M)に従って状態を更新する。なお、MとMの詳細な例については後述する。 In each vehicle, the state (x) is updated according to the dynamics (M 1 +M 2 ) under the constraint of collision avoidance (Ax+b≦0). A detailed example of M1 and M2 will be described later.
 また、本実施の形態では、常微分方程式を離散化し、(1)車両内状態更新と、(2)車両間通信を交互に繰り返す制御アルゴリズム(ニューラルネット)を構成している。 In addition, in the present embodiment, an ordinary differential equation is discretized to form a control algorithm (neural network) that alternately repeats (1) vehicle internal state update and (2) vehicle-to-vehicle communication.
 図3に、車両数がNの場合の上記制御アルゴリズムのイメージを示す。図3に示すように、初期化の後、各車両内の車両内状態更新と、各車両の近接車両との間の通信が交互に繰り返される。図3に示すように、全体の計算は分散並列化されているので、各車両での計算は軽量になる。また、車両間通信については、NW帯域を圧迫しない近接スパース通信としている。 Fig. 3 shows an image of the above control algorithm when the number of vehicles is N. As shown in FIG. 3, after the initialization, the in-vehicle state update in each vehicle and the communication between each vehicle's neighboring vehicles are alternately repeated. As shown in FIG. 3, the overall computation is distributed and parallelized, so the computation on each vehicle is lightweight. Also, inter-vehicle communication is close proximity sparse communication that does not put pressure on the NW band.
 上記のように状態更新を行うニューラルネットワークの学習(パラメータθの学習)に関しては、随伴法(Adjoint法)を用いる。すなわち、随伴法に基づくニューラルネットの逆伝搬計算による効率的な微分計算を行って、衝突抑止の制約下で平均速度を目標速度に向けて加速するようにパラメータ(θ)を学習する。本実施の形態では、パラメータ(θ)を全車両に共通としているが、各車両で異なるパラメータθを使用するように学習することも可能である。 The adjoint method is used for the neural network learning (learning the parameter θ) that updates the state as described above. That is, efficient differential calculation is performed by back propagation calculation of a neural network based on the adjoint method, and the parameter (θ) is learned so as to accelerate the average speed toward the target speed under the constraint of collision prevention. In this embodiment, the parameter (θ) is common to all vehicles, but it is also possible to learn so that each vehicle uses a different parameter θ.
 図4は、ノードが車両である場合のシステムをより具体的に示した図である。図4に示すように、複数の車両1が存在し、各車両は制御装置100を備える。制御装置100が上記のDNNのモデルを備え、状態取得、状態更新、状態出力を行う。図4の例では、制御サーバ200が備えられている。ここでは、制御サーバ200が、各車両から状態等の情報(各車両で計算されたコストでもよい)を受信し、パラメータ(θ)の学習を行って、学習済みパラメータθを各車両に送信する。 FIG. 4 is a diagram more specifically showing the system when the node is a vehicle. As shown in FIG. 4, there are a plurality of vehicles 1, each equipped with a control device 100. FIG. The control device 100 has the DNN model described above, and performs state acquisition, state update, and state output. In the example of FIG. 4, a control server 200 is provided. Here, the control server 200 receives information such as the state from each vehicle (may be the cost calculated by each vehicle), learns the parameter (θ), and transmits the learned parameter θ to each vehicle. .
 なお、制御サーバ200を備えることは一例である。制御サーバ200を備えずに、各車両が自身でパラメータθの学習を行ってもよい。 The provision of the control server 200 is an example. Each vehicle may learn the parameter θ by itself without the control server 200 .
 以下では、上述した常微分方程式と、その初期値問題を解く技術の具体例について詳細に説明する。 In the following, specific examples of techniques for solving the above-mentioned ordinary differential equations and their initial value problems will be explained in detail.
 (NOSの概要)
 常微分方程式の初期値問題(IVP:Initial Value Problems)を解くためのDNNのモデルとして、ニューラル常微分方程式(NODE:Neural Ordinary Differential Equation)が提案されている。
(Overview of NOS)
A Neural Ordinary Differential Equation (NODE) has been proposed as a DNN model for solving Initial Value Problems (IVPs) of ordinary differential equations.
 NODEにおいて、初期状態x(0)を持つ状態変数x(t)、学習可能パラメータθ、及び時刻tを有する非線形ダイナミクスMが与えられることで、IVPが定式化される。図5に、NODEに基づくDNNアーキテクチャを示す。図5に示すように、状態が順次更新され、各状態に基づきコスト計算がなされる。 In NODE, given a state variable x(t) with an initial state x(0), a learnable parameter θ, and a nonlinear dynamics M with time t, the IVP is formulated. FIG. 5 shows a NODE-based DNN architecture. As shown in FIG. 5, the states are updated sequentially and the cost is calculated based on each state.
 一方、本実施の形態では、更に外部制御入力o(t)を導入しており、この点はNODEにはない点である。この場合、IVPを下記の式(1)により定義することができる。 On the other hand, in the present embodiment, an external control input o(t) is further introduced, which NODE does not have. In this case, IVP can be defined by the following equation (1).
 ∂x/∂t=M(x,o,θ,t) (1)
 なお、上記の式(1)におけるxとoの時間インデックスは、表記を簡略化するために省略している。
∂x/∂t=M(x, o, θ, t) (1)
Note that the time indices of x and o in equation (1) above are omitted for simplicity of notation.
 NODEに基づくDNNアーキテクチャは、基本的なIVPの離散化として構築することができるので、ODEソルバにおける種々の離散化方法、例えば、高次Runge-Kuttaソルバが、種々のNODEベースDNNアーキテクチャを構築するために利用可能である。 Since the NODE-based DNN architecture can be constructed as a basic IVP discretization, different discretization methods in ODE solvers, such as higher-order Runge-Kutta solvers, construct different NODE-based DNN architectures. available for
 NODEにより基本的なIVPを扱うことができるが、多くのサブシステム(ノード)とそれらの接続(エッジ)から構成されるグラフとして表すことができる複雑なダイナミクスMを持つ大規模システムへの適用は難しい。このようなシステムの例は、前述した交通整流を行う複数の車両からなるシステムである。 Although NODE allows us to handle basic IVPs, its application to large-scale systems with complex dynamics M, which can be represented as a graph consisting of many subsystems (nodes) and their connections (edges), is difficult. An example of such a system is the system of vehicles that rectifies traffic as described above.
 また、NODEのような集中型の計算方法では、大規模システムに対して、式(1)における順方向伝搬(x遷移)と逆方向伝搬(θの学習)を実行することは困難である。 Also, in a centralized computation method such as NODE, it is difficult to execute forward propagation (x transition) and backward propagation (learning θ) in Equation (1) for a large-scale system.
 上記のノードとエッジからなるシステムにおいては、(i)各ノードにおける状態遷移(例:各車両における速度状態更新)および(ii)ノード間のメッセージパッシング(例:近接配置された車両間の通信)を繰り返しながら、分散方式で処理を実行することが有効である。 In the above system consisting of nodes and edges, (i) state transitions at each node (e.g. speed state update at each vehicle) and (ii) message passing between nodes (e.g. communication between closely spaced vehicles) It is effective to execute processing in a distributed manner while repeating
 この問題に対処するために、本実施の形態では、NODEの拡張としてニューラル作用素分解(NOS: Neural Operator Splitting)を用いた連合ダイナミクス学習(federated dynamics learning)を採用している。その概要は下記のとおりである(詳細は後述)。 To address this problem, the present embodiment adopts federated dynamics learning using neural operator splitting (NOS) as an extension of NODE. The outline is as follows (details will be described later).
 全体のダイナミクスMは、(i)各ノードの状態遷移のためのMと、(ii)グラフ形式の大規模システムを効率的に管理するためのノード間のメッセージパッシングのためのMに分解され、下記の式(2)のように表される。 The overall dynamics M is decomposed into (i) M1 for state transitions of each node and (ii) M2 for message passing between nodes for efficient management of large-scale systems in graph form. and is represented by the following formula (2).
 ∂x/∂t=M(x,o,θ,t)+M(x,o,t)  (2)
 ここで、Mは各ノードにおけるサブダイナミクスに更に分解することができる。Mは、メッセージパッシングに関連しているので、学習可能なパラメータを持たないように設定される。
∂x/∂t=M 1 (x, o, θ, t) + M 2 (x, o, t) (2)
Here, M1 can be further decomposed into sub-dynamics at each node. M2 is set to have no learnable parameters as it relates to message passing.
 また、公知技術であるPRS(Peaceman-Rachford Splitting)およびDRS(Douglas-Rachford Splitting)のような作用素分解法を用いて上記の(2)を離散化することにより、状態遷移は残差(residual)、再帰(recurrent)、及び交互(alternating)の形式とすることができる。 In addition, by discretizing the above (2) using the known techniques of operator decomposition such as PRS (Peaceman-Rachford Splitting) and DRS (Douglas-Rachford Splitting), the state transition is the residual , recurrent, and alternating forms.
 また、本実施の形態では、物理的制約を課すために状態ドメイン緩和を行っている。すなわち、式(2)では、Mの状態ドメインとMの状態ドメインはxとして同一であるが、本実施の形態のNOSでは、多くのノードの状態変数に物理的制約を課すために、式(2)の状態ドメインの制約を緩和する。 Also, in this embodiment, state domain relaxation is performed to impose physical constraints. That is, in equation (2), the state domain of M1 and the state domain of M2 are the same as x, but in the NOS of this embodiment, in order to impose physical constraints on the state variables of many nodes, Relax the state domain constraint of equation (2).
 具体的には、Mに対してはxを使用し、Mに対しては、{A,b}を与えて、補助状態変数y=Ax+bを使用して、M(y,o,t)とする。y=Ax+bは物理的制約を表し、例えばy=Ax+b≦0とする。すなわち、(i)各車両速度(Nノード{x,...,x}∈xの状態)は、Mに従い更新されつつ、(ii)例えば不等式を使用することでy=Ax+b≦0としてMを設計することにより、他の車両との間である距離が保たれる。これにより、適切にパラメータサーチエリアが限定され、例えば、車両の衝突を防ぎ、θの学習が迅速かつ安定的に行われることが期待される。 Specifically, using x for M 1 and giving {A,b} for M 2 , using the auxiliary state variable y=Ax+b, M 2 (y,o, t). y=Ax+b represents a physical constraint, for example y=Ax+b≦0. That is, (i) each vehicle velocity (state of N nodes {x 1 ,..., x N }εx) is updated according to M 1 while (ii) y=Ax+b≦ By designing M2 as 0, some distance is preserved between other vehicles. As a result, it is expected that the parameter search area will be appropriately limited, that, for example, vehicle collisions will be prevented, and that .theta. will be learned quickly and stably.
 なお、後述するように、本実施の形態では、ADMM法(Alternating Direction Method of Multipliers、交互方向乗数法)によって導かれた制約付きコスト最小化問題にNOSを関連付けることとしている。 As will be described later, in the present embodiment, NOS is associated with a constrained cost minimization problem derived by the ADMM method (Alternating Direction Method of Multipliers).
 (状態空間モデルに従う拡張NODE)
 NOSの詳細説明を行う前に、NOSに関連する技術として、ここでは状態空間モデルに従う拡張NODEについて説明する。これは、実アプリケーションにおける、状態変数xに対する、ノイジーであり、非線形であり、間接的である観測過程を仮定した状態空間モデルに従う拡張NODEベースDNNアーキテクチャである。
(extended NODE following the state-space model)
Before describing NOS in detail, extended NODE according to the state space model will be described here as a technology related to NOS. It is an extended NODE-based DNN architecture following a state-space model assuming a noisy, nonlinear, and indirect observation process for the state variable x in real applications.
 以下では、最初に、観測過程を考慮に入れたコスト関数を定義する。次に、4D-Varにより、xの学習のための随伴法と上記コスト関数の中のパラメータθを定式化し、状態空間モデルに従う拡張NODEベースのDNNアーキテクチャを導出する。 Below, we first define a cost function that takes into account the observation process. Next, with 4D-Var, we formulate the adjoint method for learning x and the parameter θ in the above cost function, and derive an extended NODE-based DNN architecture that follows the state-space model.
 <コスト関数導出>
 状態変数x(t)が時間間隔t∈(0,T)で式(1)に従って逐次更新されると仮定する。初期状態x(0)と外部制御入力o(t)が与えられると、式(1)は下記の積分形式の式(3)に書き換えることができる。
<Cost function derivation>
Assume that the state variable x(t) is successively updated according to equation (1) at time intervals tε(0,T). Given an initial state x(0) and an external control input o(t), equation (1) can be rewritten into equation (3) in integral form below.
Figure JPOXMLDOC01-appb-M000001
 状態空間モデルに合わせて、観測システムHを通じて、x(t)の間接的な観測を許容する。システムの理想的な振る舞い(例:理想制御状態)がr(t)で与えられる場合、時刻tにおけるコスト関数は、下記の式(4)
Figure JPOXMLDOC01-appb-M000001
In keeping with the state-space model, we allow an indirect observation of x(t) through the observation system H. If the ideal behavior of the system (e.g. ideal control state) is given by r(t), the cost function at time t is the following equation (4)
Figure JPOXMLDOC01-appb-M000002
により表すことができる。
Figure JPOXMLDOC01-appb-M000002
can be represented by
 式(4)において、R(t)は測定ノイズξの共分散行列であり、は行列の転置を表す。測定ノイズはガウス分布ξ~Norm(0,υ)に従うと仮定すると、特定のR(t)としてスケーリングされた単位行列を選択できる。x(0)からx(T)への状態遷移は式(1)によって制約されるので、θの学習のための最終コスト形式J(x,θ)は、下記の式(5)のとおり、制約付きコスト積分最小化問題によって与えられる。 (4), R(t) is the covariance matrix of the measurement noise ξ, and T represents the transpose of the matrix. Assuming that the measurement noise follows a Gaussian distribution ξ ~ Norm(0, ν 2 ), we can choose a scaled identity matrix as a particular R(t). Since the state transitions from x(0) to x(T) are constrained by equation (1), the final cost form J(x, θ) for learning θ is given by equation (5) below: given by the constrained cost integral minimization problem.
Figure JPOXMLDOC01-appb-M000003
 <ダイナミクス学習のための随伴法>
 次に、適切な汎関数の一次変分を0にするθを見つける問題を解く。まず、式(5)に基づいて、ラグランジュ変数(随伴変数)
Figure JPOXMLDOC01-appb-M000003
<Adjoint method for dynamics learning>
Next, solve the problem of finding θ that makes the first-order variation of the appropriate functional zero. First, based on equation (5), Lagrangian variables (adjoint variables)
Figure JPOXMLDOC01-appb-M000004
を有するラグランジュ関数L(x,λ,θ,t)を定式化する。変分問題は、汎関数δLの一次変分を0とするθを見つけることである。結果として得られる随伴式は、下記の式(6)のとおりである。
Figure JPOXMLDOC01-appb-M000004
We formulate a Lagrangian function L(x, λ, θ, t) with The variational problem is to find θ such that the first-order variation of the functional δL is zero. The resulting adjoint equation is shown below in equation (6).
Figure JPOXMLDOC01-appb-M000005
 ここで、{M(t),Mθ(t)}は、Mのヤコビアンであり、は、自然内積〈,〉に対する随伴作用素であり、〈Mx,λ〉=〈x,Mλ〉を満たす。また、ユークリッド整域を仮定してM=Mを使用している。なお、電子出願の明細書で使用できる文字種の制約上、随伴作用素の記号として、明細書では、を使用している。
Figure JPOXMLDOC01-appb-M000005
where {M x (t), M θ (t)} is the Jacobian of M, * is the adjoint operator for the natural inner product <,>, and <Mx, λ>=<x, M * λ 〉 is satisfied. We also use M * =M T assuming a Euclidean domain. Due to restrictions on the types of characters that can be used in electronic application specifications, * is used in the specification as the symbol for the adjoint operator.
 また、式(4)より、 Also, from formula (4),
Figure JPOXMLDOC01-appb-M000006
が成り立つ。ここで、H(t)は、x(t)に関するHのヤコビアンである。
Figure JPOXMLDOC01-appb-M000006
holds. where H x (t) is the Jacobian of H with respect to x(t).
 初期化をλ(T)=0とし、随伴変数λ(t)は、逆方向に更新され、結果として、λ(0)=g=[g x0,g θを得る。ここで、gは、時刻0でのコスト関数Jの勾配である。コスト関数の勾配は、下記の式(7)ように、随伴式を時間で逆方向に積分することにより得ることができる。 Let the initialization be λ(T)=0 and the adjoint variable λ(t) is updated backwards, resulting in λ(0)=g=[g T x0 , g T θ ] T . where g is the slope of the cost function J at time zero. The slope of the cost function can be obtained by integrating the adjoint equation backwards in time, as shown in Equation (7) below.
Figure JPOXMLDOC01-appb-M000007
 観測過程が些細である場合、NODEで想定されるように、式(4)のHは、恒等作用素である。随伴法において、最適なダイナミクスモデルMのθの学習は、gθを用いて、交互に/繰り返し、連続的な順方向伝搬(3)と連続的な逆方向伝搬(7)を実行することにより行われる。
Figure JPOXMLDOC01-appb-M000007
If the observation process is trivial, H in equation (4) is the identity operator, as assumed in NODE. In the adjoint method, the learning of θ for the optimal dynamics model M is performed by alternately/repeatingly performing successive forward propagation (3) and successive backward propagation (7) using g done.
 <NODEベースのDNNアーキテクチャ>
 NODEに基づくいくつかのDNNアーキテクチャは、式(1)の離散化により得られる。表記を簡単にするために、xを離散時間t(k=1,...,K)における推定されたシステム状態とし、Dにより、離散時間間隔ΔtでのMを介した残差状態更新の近似を行う。
<NODE-based DNN architecture>
Several NODE-based DNN architectures are obtained by discretization of equation (1). For simplicity of notation, let x k be the estimated system state at discrete times t k (k=1, . . . , K), and let D denote the residual state through M Make an approximation of the update.
 与えられた状態変数{θ,o}が、xk+1=D(x)として残差及び再帰形式で更新される。Dは、D=Dq-1・・・Dとして、作用素の集合からなることが許容される。 A given state variable {θ,o} is updated in residual and recursive form as x k+1 =D(x k ). D is allowed to consist of a set of operators, D=D q D q−1 . . . D 1 .
 下記に示す前進オイラー法(8)、後退オイラー法(9)、及びクランクニコルソン法(2次ルンゲクッタ)を、離散状態遷移ルールを有する微分方程式の近似に使用することができる。 The forward Euler method (8), backward Euler method (9), and Crank-Nicholson method (second-order Runge-Kutta) shown below can be used to approximate differential equations with discrete state transition rules.
 [前進オイラー法] [Forward Euler method]
Figure JPOXMLDOC01-appb-M000008
 [後退オイラー法]
Figure JPOXMLDOC01-appb-M000008
[Backward Euler method]
Figure JPOXMLDOC01-appb-M000009
 [クランクニコルソン法]
Figure JPOXMLDOC01-appb-M000009
[Crank-Nicholson method]
Figure JPOXMLDOC01-appb-M000010
ここで、Mo,θは、{θ,o}が与えられたMを表し、Idは、恒等作用素を表し、-1は逆作用素を表す。クランクニコルソン法において、xk+1=D(x)は、
Figure JPOXMLDOC01-appb-M000010
where M o,θ represents M given {θ,o k }, Id represents the identity operator, and −1 represents the inverse operator. In the Crank-Nicholson method, x k+1 =D(x k ) is
Figure JPOXMLDOC01-appb-M000011
に分解される。
Figure JPOXMLDOC01-appb-M000011
is decomposed into
 NODEベースのDNNアーキテクチャは、図5、図6に示すように、残差状態更新((8)、(9)、又は(10))に基づくK回の繰り返しの再帰スタックに対して使用可能である。なお、前進オイラー法はResNetと見なすことができる。 The NODE-based DNN architecture can be used for recursive stacks of K iterations based on residual state updates ((8), (9), or (10)) as shown in FIGS. be. Note that the forward Euler method can be regarded as a ResNet.
 随伴法は、θの学習における勾配の計算に使用することができる。この場合、NODEベースのDNNアーキテクチャは、下記の式(11)に示すように、連続逆方向伝搬(7)を離散化することにより図6に従うように拡張される。 The adjoint method can be used to calculate the gradient in learning θ. In this case, the NODE-based DNN architecture is extended to follow FIG. 6 by discretizing the continuous backward propagation (7), as shown in equation (11) below.
Figure JPOXMLDOC01-appb-M000012
 ここでは、初期値λ=0が与えられる。また、Dは、Mの離散化表現である。Mが作用素の集合からなり、随伴作用素が、ユークリッド整域において定義される場合、ヤコビアンは、
Figure JPOXMLDOC01-appb-M000012
Here, an initial value λ K =0 is given. Also, D is a discretized representation of M. If M consists of a set of operators and the adjoint operator * is defined in the Euclidean domain, then the Jacobian is
Figure JPOXMLDOC01-appb-M000013
として分解される。残差及び再帰更新(11)により、勾配λ=gが得られ、θの更新が行われる。
Figure JPOXMLDOC01-appb-M000013
is decomposed as The residual and recursive update (11) gives the gradient λ 0 =g and updates θ.
 ここでは、状態空間モデルに従うNODEベースのDNNアーキテクチャを導入した。しかし、複数車両が自律的に交通整流を行う場合のように、全体のシステムのダイナミクスが複雑になると、このアプローチでは計算量的に難しくなる。 Here, we introduced a NODE-based DNN architecture that follows the state-space model. However, when the dynamics of the overall system become complex, such as when multiple vehicles rectify traffic autonomously, this approach becomes computationally difficult.
 そこで、本実施の形態では、連合ダイナミクス学習のためのNOSベースのDNNアーキテクチャを導入し、車両状態更新(i)と、車両間でのメッセージパッシング(ii)メッセージを交互に行うことで、交通整流問題を解くこととしている。 Therefore, in the present embodiment, a NOS-based DNN architecture for federated dynamics learning is introduced, and traffic rectification is achieved by alternately performing vehicle state updating (i) and message passing (ii) between vehicles. I am trying to solve the problem.
 (ニューラル作用素分解(NOS))
 以下、連合ダイナミクス学習のためのNOSベースのDNNアーキテクチャについて詳細に説明する。最初に、PRSとDRS等の作用素分解方法を用いた式(2)の離散化について説明する。次に、NOSが、{M,M}における状態変数のドメイン緩和のための制約付きコスト最小問題に関連付けられることを説明する。これは、大規模な分散システムにおける状態変数を管理するために重要である。更に、ノードの状態遷移(i)とノード間のメッセージパッシング(ii)を繰り返す連合ダイナミクス学習にための{M,M}の形を特定する。
(Neural operator decomposition (NOS))
In the following, the NOS-based DNN architecture for federated dynamics learning is described in detail. First, discretization of equation (2) using operator decomposition methods such as PRS and DRS will be described. Next, we show that NOS is related to the constrained minimum cost problem for domain relaxation of state variables in {M 1 , M 2 }. This is important for managing state variables in large distributed systems. Furthermore, we specify the form of {M 1 , M 2 } for federated dynamics learning that repeats node state transitions (i) and inter-node message passing (ii).
 <作用素分解による離散化>
 作用素分解法を用いた式(2)の離散化について説明する。NOSでは、PRS、DRS、およびFBS(Forward-Backward Splitting)等の様々な作用素分解法を利用可能である。
<Discretization by operator decomposition>
Discretization of equation (2) using the operator decomposition method will be described. Various operator decomposition methods such as PRS, DRS, and FBS (Forward-Backward Splitting) are available in NOS.
 本実施の形態では、これらの中で、PRSとDRSを選択している。その理由は、それらは二次精度を有するクランクニコルソン法(10)に基づくので、両方とも正確な状態遷移を達成することが期待されるからである。 In the present embodiment, PRS and DRS are selected among these. Because they are based on the Crank-Nicholson method (10) with second-order accuracy, both are expected to achieve accurate state transitions.
 PRSを用いた式(2)の離散化により、下記の式(12)に示すように、残差、再帰、および交互のDNNアーキテクチャを得ることができる。
[PRS-Net]
Discretization of equation (2) with PRS yields residual, recursive, and alternating DNN architectures, as shown in equation (12) below.
[PRS-Net]
Figure JPOXMLDOC01-appb-M000014
 式(12)において、クランクニコルソン法に基づく2つの残差状態の更新CΔt/2‐Miが、交互に適用される。他の作用素分解に関して、DRSを式(2)の離散化に適用すると、下記の式(13)のように、残留、再帰、及び交互の形式が得られる。
[DRS-Net]
Figure JPOXMLDOC01-appb-M000014
In equation (12), two residual state updates C Δt/2-Mi based on the Crank-Nicholson method are applied alternately. For other operator decompositions, applying DRS to the discretization of equation (2) yields residual, recursive, and alternating forms, as in equation (13) below.
[DRS-Net]
Figure JPOXMLDOC01-appb-M000015
 PRS-NetおよびDRS-NetのDNNアーキテクチャを図7に示す。式(12)と式(13)から、DRS-Netはステップサイズの2倍の平均化操作を使用する点で、PRS-NetとDRS-Netは異なる。NOS(PRS-NetやDRS-Netなど)でのθの学習は、前述した随伴法に従って行うことができる。
Figure JPOXMLDOC01-appb-M000015
The DNN architectures of PRS-Net and DRS-Net are shown in FIG. From equations (12) and (13), PRS-Net and DRS-Net differ in that DRS-Net uses an averaging operation of twice the step size. Learning of θ in NOS (PRS-Net, DRS-Net, etc.) can be performed according to the adjoint method described above.
 状態遷移は残差作用素のセットD=Dq-1・・・Dによって行われるため、θの学習の勾配は、式(11)のD=D ・・・D を置き換えることによって得ることができる。 Since the state transitions are performed by the set of residual operators D=D q D q 1 . It can be obtained by replacing D q T.
 <柔軟なサブダイナミクス連携のための状態ドメインの緩和>
 ここでは、NOS(PRS-NetおよびDRS-Net)を、2つのサブダイナミクス{M,M}の状態ドメイン緩和のための制約付きコスト最小化問題と関連付ける。
<Relaxation of state domain for flexible subdynamics cooperation>
Here we associate the NOS (PRS-Net and DRS-Net) with the constrained cost minimization problem for state-domain relaxation of two subdynamics {M 1 , M 2 }.
 Mの状態変数がx(t)の場合、Mの状態変数はy(t)=A(t)x(t)+b(t)で緩和される。ここで、{A,b}の時間インデックスを省略し、表記を簡略化する。また、任意のtについて逆行列(AA)-1が存在するようにAが選択されることとする。 If the state variable of M1 is x(t), then the state variable of M2 is relaxed with y(t)=A(t)x(t)+b(t). Here we omit the time index in {A,b} to simplify the notation. Also, let A be chosen such that there is an inverse matrix (A T A) −1 for any t.
 ADMMフローについて、これは、連続ODE形式の(離散)ADMMを作成するために、離散時間の制限を考慮している。ADMMフローにおいて、{M,M}は、(AA)-1を使用したアフィン変換で最小化されるコスト関数Vの(劣)微分によって特定される。 For the ADMM flow, it takes into account the discrete time limitation to create a continuous ODE form of (discrete) ADMM. In the ADMM flow, {M 1 , M 2 } are specified by the (sub)differential of the cost function V minimized with an affine transformation using (A T A) −1 .
 本実施の形態では、これに基づき、下記の式(14)ように、関数VをV=V+Vのように分解することにより{M,M}を設定している。ここで、Vは滑らかであるが、非凸関数であり、Vは凸関数であるが、微分できない場合がある。 Based on this, in the present embodiment, {M 1 , M 2 } are set by decomposing the function V into V=V 1 +V 2 as in the following equation (14). where V1 is a smooth but non-convex function and V2 is a convex function but may not be differentiable.
Figure JPOXMLDOC01-appb-M000016
 また、∂は劣微分作用素を示す。なお、式(14)は、次の点でADMMフローと異なる:(i)Vにおけるパラメータθは学習可能であり、非凸状である、(ii)Vは、微分可能でない可能性がある、(iii)変換の一般化のためにバイアスbが加えられている、(iV){A,b}は、時変であり得る。
Figure JPOXMLDOC01-appb-M000016
Also, ∂ indicates a subdifferential operator. Note that equation (14) differs from the ADMM flow in the following ways: (i) the parameter θ in V 1 is learnable and non-convex, (ii) V 2 may not be differentiable One, (iii) a bias b is added for generalization of the transform, (iv) {A,b} can be time-varying.
 式(14)の物理的意味を調べるために、これを制約付きのコスト最小化問題に関連付ける。この目的のために、ここでは{V,V}を凸に制限し、制約パラメータ{A,b}を時不変とする。線形制約付き凸最小化問題は次の式(15)で与えられる。 To explore the physical meaning of equation (14), we relate it to the constrained cost minimization problem. For this purpose, we constrain {V 1 , V 2 } to be convex and make the constraint parameters {A, b} time-invariant. A linearly constrained convex minimization problem is given by the following equation (15).
Figure JPOXMLDOC01-appb-M000017
 {V,V}は凸に制限されているので、{∇V,∂V}は、その逆作用素{(∇V-1,(∂V-1}を持つ。そして、式(15)の双対問題は下記の式(16)で与えられる。
Figure JPOXMLDOC01-appb-M000017
Since {V 1 ,V 2 } is constrained to be convex, {∇V 1 ,∂V 2 } has its inverse {(∇V 1 ) −1 ,(∂V 2 ) −1 }. Then, the dual problem of Equation (15) is given by Equation (16) below.
Figure JPOXMLDOC01-appb-M000018
 ここで、式(15)における制約に関するラグランジュ係数はzで表され、凸共役関数V (Az)=sup(〈z,Ax〉-V(x))およびV (-z)=sup(-〈z,y〉-V(y))で使用される。ここで∇V =(∇V-1および∂V =(∂V-1である。
Figure JPOXMLDOC01-appb-M000018
where the Lagrangian coefficients for the constraints in Eq . -z)=sup y (-<z,y>-V 2 (y)). where ∇V 1 * =(∇V 1 ) −1 and ∂V 2 * =(∂V 2 ) −1 .
 式(16)にDRSを適用すると、よく知られているADMMアルゴリズムが得られる。これにより、離散ステップにおける、残留、再帰、交互の形式により{x,y,z}を更新する。 Applying DRS to equation (16) yields the well-known ADMM algorithm. This updates {x, y, z} in a residual, recursive, alternating manner in discrete steps.
 式(14)のVは非凸である可能性があるが、Δtが十分に小さい場合に、下記の式(17)のように、前の状態xk-1の周りにおいてテーラー展開することで、局所二次形式で近似できる。 V 1 in equation (14) can be non-convex, but if Δt is small enough, it can be Taylor expanded around the previous state x k−1 as in equation (17) below can be approximated by a local quadratic form.
Figure JPOXMLDOC01-appb-M000019
 ここで、Vのヘッセ行列は、α>0を使用してスケーリングされた単位行列で近似される。PRS-Net(12)とDRS-Net(13)は、{V,V}が凸であり、{A,b}が時不変であるという前提の下で式(15)を解く点で一貫性がある。
Figure JPOXMLDOC01-appb-M000019
Here the Hessian matrix of V 1 is approximated by a scaled identity matrix using α>0. PRS-Net(12) and DRS-Net(13) solve equation (15) under the assumption that {V 1 , V 2 } are convex and {A, b} are time-invariant in that Consistent.
 <連合ダイナミクス学習のためのコスト関数仕様>
 ここで、連合ダイナミクス学習のために、式(14)における{V,V}を規定する。この目的のために、グラフ表記の記号(シンボル)を導入する。本実施の形態に係る交通整流問題に対して、車両(ノード)間の接続(エッジ)は時間的に変化する。したがって、時変グラフG(t)を使用する。
<Cost function specification for federated dynamics learning>
We now define {V 1 , V 2 } in equation (14) for federated dynamics learning. For this purpose, we introduce symbols of graphical notation. For the traffic control problem according to this embodiment, connections (edges) between vehicles (nodes) change over time. Therefore, we use the time-varying graph G(t).
 G(t)は、N(t)個のノードの集合N(t)とE(t)個のエッジの集合E(t)からなる。i番目のノードに接続された隣接車両のインデックスの集合は、E(t)={j∈N(t)|(i,j)∈E(t)}で表される。以降、{G(t),N(t),E(t)}の時間インデックスを省略する。 G(t) consists of a set N(t) of N(t) nodes and a set E(t) of E(t) edges. The set of indices of neighboring vehicles connected to the i-th node is represented by E i (t)={jεN(t)|(i,j)εE(t)}. Hereafter, we omit the time index of {G(t), N(t), E(t)}.
 各ノードには、それ自身のコスト関数Vlocal,i(x,o,θ,t)を持つ動的サブシステムが存在する。全体的な観点からは、入力変数スタックは、時変変数x=[x ,...,x ,o=[o ,...,o と時不変変数θ=[θ ,...,θ からなる。 At each node there is a dynamic subsystem with its own cost function V local,i (x i ,o ii ,t). From a global point of view, the input variable stack consists of time-varying variables x=[ x1T ,..., xNT ] T , o=[ o1T , ..., oNT ] T and time consists of invariant variables θ=[θ 1 T , . . . , θ N T ] T .
 表記を簡略化するために、制御入力oには、エッジ情報Eと、状態xと隣接ノードの状態x(j∈E)を関連付けるための時変制約パラメータ{Ai|j,bi|j}が含まれるものとする。{Ai|j,bi|j}のスタックは、式(14)における{A,b}と下記のようにして関連付けられる。 To simplify the notation, the control input o i includes the edge information E i and the time-varying constraint parameters {A i|j , b i|j }. The stack of {A i|j ,b i|j } is associated with {A,b} in equation (14) as follows.
Figure JPOXMLDOC01-appb-M000020
 連合ダイナミクス学習のために、状態遷移に関するコスト関数を下記の式(18)のように定式化する。
Figure JPOXMLDOC01-appb-M000020
For federated dynamics learning, a cost function for state transition is formulated as shown in Equation (18) below.
Figure JPOXMLDOC01-appb-M000021
 本実施の形態における交通整流問題において、(i)Vlocal,iは、目標に向けて速度状態を加速するように設計されており、(ii)不等式制約が、車両間距離を維持するように設計されている。
Figure JPOXMLDOC01-appb-M000021
In the traffic rectification problem in this embodiment, (i) V local,i is designed to accelerate the velocity state towards the target, and (ii) inequality constraints are designed to maintain inter-vehicle distance Designed.
 不等式の制約は(I+P)(Ax+b)≦0と表すことがきる。ここで、P(o,t)は、時変グラフGに従う隣接ノード間での変数の交換を規定する置換行列である。制約が指示関数で表される場合、式(18)は下記の式(19)のように表記できる。 The inequality constraint can be expressed as (I + P) (Ax + b) ≤ 0. where P(o,t) is a permutation matrix that defines the exchange of variables between adjacent nodes following the time-varying graph G. If the constraint is represented by an indicator function, Equation (18) can be expressed as Equation (19) below.
Figure JPOXMLDOC01-appb-M000022
 指示関数は下記の式(20)ように表される。
Figure JPOXMLDOC01-appb-M000022
The indicator function is expressed as Equation (20) below.
Figure JPOXMLDOC01-appb-M000023
 制約付き最適化問題(15)は、ODE形式(14)と一貫性を持つため、{V,V}は、連合ダイナミクス学習に対し、下記の式(21)により規定することができる。
Figure JPOXMLDOC01-appb-M000023
Since the constrained optimization problem (15) is consistent with the ODE form (14), {V 1 , V 2 } can be defined by equation (21) below for federated dynamics learning.
Figure JPOXMLDOC01-appb-M000024
 以上、説明したように、二次近似(17)を有するコスト関数(21)が、PRS-Net(12)およびDRS-Net(13)におけるダイナミクス(14)へ代入されることで、連合ダイナミクス学習のためのNOSベースのDNNアーキテクチャが規定される。
Figure JPOXMLDOC01-appb-M000024
As described above, the cost function (21) having the quadratic approximation (17) is substituted into the dynamics (14) in PRS-Net (12) and DRS-Net (13), so that federated dynamics learning A NOS-based DNN architecture for is defined.
 (自律車両の分散交通整流)
 NOSを応用した交通整流を実現する分散制御システムの動作について詳細に説明する。各車両は、外部制御入力(例えば、カメラ/LiDARからの入力)および近接する車両間のメッセージパッシングを使用して、自律的にその状態(例えば、速度)を更新する。
(Distributed traffic rectification for autonomous vehicles)
The operation of a distributed control system that implements NOS-applied traffic rectification will now be described in detail. Each vehicle autonomously updates its state (eg, speed) using external control inputs (eg, inputs from cameras/LiDAR) and message passing between nearby vehicles.
 当該分散制御システムの挙動は状態遷移ダイナミクスの関数であり、入力は前の状態xと制御入力oである。また、NOSベースの連合ダイナミクス学習を用いて状態遷移ダイナミクスのパラメータθを最適化している。  The behavior of the distributed control system is a function of state transition dynamics, and the inputs are the previous state x and the control input o. Also, NOS-based federated dynamics learning is used to optimize the parameter θ of the state transition dynamics.
 以下、まず、分散交通整流に関連する関連技術の概要を説明する。次に、車間距離を保つことで衝突を回避しつつ、平均車速を目標速度まで加速するシグナルフリー交通整流のための、式(21)における{J,V,A,b}を説明する。そして、PRS‐NetとDRS‐Netに基づく状態遷移DNNアーキテクチャの導出について説明する。 Below, first, an overview of related technologies related to distributed traffic rectification will be explained. Next, {J, V, A, b} in Eq. (21) for signal-free traffic rectification that accelerates the average vehicle speed to the target speed while avoiding collision by maintaining inter-vehicle distance will be described. Then, derivation of state transition DNN architecture based on PRS-Net and DRS-Net will be described.
 <関連技術>
 交通整流に関する関連技術として、例えば、参考文献「Wang, Z., Zheng, Y., Li, S. E., You, K., and Li, K. (2018). Parallel optimal control for cooperative automation of large-scale connected vehicles via admm.」に開示された技術がある。
<Related technology>
Related technologies related to traffic rectification include, for example, the reference "Wang, Z., Zheng, Y., Li, S. E., You, K., and Li, K. (2018). Parallel optimal control for cooperative automation of large-scale connected vehicles via admm."
 本技術では、車両間の距離をある距離に保ちつつ、各車両を目標速度にするためにADMMを使用することが記載されている。しかし、次のような問題がある:(i)車両ノードを接続するために余計なリンクノードが必要となる;(ii)状態遷移ダイナミクスにおいて、学習可能パラメータが存在しない。 This technology describes using an ADMM to set each vehicle to a target speed while maintaining a certain distance between vehicles. However, there are problems: (i) extra link nodes are needed to connect vehicle nodes; (ii) there are no learnable parameters in the state transition dynamics.
 これに対し、本実施の形態に係る技術では、(i)車両ノードのみからなる完全に分散化した交通整流を実現するとともに、(ii)最適自律状態遷移ダイナミクスを得るための連合ダイナミクス学習を実現している。 On the other hand, the technology according to the present embodiment (i) realizes completely decentralized traffic rectification consisting only of vehicle nodes, and (ii) realizes federated dynamics learning for obtaining optimal autonomous state transition dynamics. are doing.
 <分散交通整流のための連合ダイナミクス学習>
 まず、交通整流問題用に、式(4)、式(21)における{J,Vlocal,i}の定式化を行う。
<Federated dynamics learning for distributed traffic rectification>
First, {J, V local, i } in equations (4) and (21) are formulated for the traffic rectification problem.
 N台の自律車両(ノード)について、それらのルート、初期速度状態、位置、及び最大速度smax[m/s]が与えられた場合に、各車両は、正規化された速度状態x=[x,...,x,(x∈[0,1])を決定するための共通の学習可能パラメータセットθ(=θ=,...,=θ)を保持すると考える。なお、明細書の文字種の制約のために、明細書においては、文字の頭に記載するバーを「θ」のように文字の前に記載している。 For N autonomous vehicles (nodes), given their routes, initial velocity states, positions, and maximum velocities s max [m/s], each vehicle has a normalized velocity state x=[ Let us define a common set of learnable parameters θ(= θ1 =, ...,=θN) for determining x1,...,xN]T , ( xi [0,1]) think to keep. In addition, due to restrictions on the type of characters used in the specification, a bar at the beginning of the character is indicated in front of the character, such as “ ”.
 分散化された信号フリー交通整流のための連合ダイナミクス学習のゴールは、車両間である距離を保って衝突を回避しながら、x(t)を目標xtar∈[0,1]に近付ける最適なθを見つけることである。 The goal of federated dynamics learning for decentralized signal-free traffic rectification is to keep x i (t) close to the target x tar ε[0,1] while keeping some distance between vehicles to avoid collisions. Na- is to find θ.
 そこで、本実施の形態では、式(4)におけるコスト関数として、下記の関数を選択している。 Therefore, in the present embodiment, the following function is selected as the cost function in Equation (4).
Figure JPOXMLDOC01-appb-M000025
 簡単な例として、次のシナリオを想定する。
Figure JPOXMLDOC01-appb-M000025
As a simple example, assume the following scenario.
 各車両が単一レーン道路の中心を走行し、追越しは禁止されている。すなわち、各車両は他の車両に追従し、交差点を横断する。各車両の制御入力oは、正規化された速度ospd,i、2D方向ベクトルodir,i、2D位置ベクトルopos,i、各車両の周囲画像oimg,i、マッピングベクトルomap,i|j、及び、隣接接続の集合j∈Eを含む。マッピングベクトルomap,i|jは、2D位置を、i番目の車両からj番目の車両までの距離を測るためのスカラー値に変換するためのものである。 Each vehicle runs in the center of a single-lane road and overtaking is prohibited. That is, each vehicle follows the other vehicle across the intersection. The control inputs o i of each vehicle are the normalized velocity o spd,i , the 2D direction vector o dir,i , the 2D position vector o pos,i , the surrounding image o img,i of each vehicle, the mapping vector o map, i|j and the set jεE i of neighboring connections. The mapping vector o map,i|j is for converting the 2D positions into scalar values for measuring the distance from the i th vehicle to the j th vehicle.
 コスト関数local(=Vlocal,1=,…,=Vlocal,N)は、式(17)に示すような二次関数により速度状態x(t)を推定するように設計されている。当該二次関数は、学習可能な加速度 The cost function - V local (=V local,1 =,...,=V local,N ) is designed to estimate the velocity state x i (t) by a quadratic function as shown in equation (17). there is The quadratic function is the learnable acceleration
Figure JPOXMLDOC01-appb-M000026
を含む。この項は、ρ∈(0,1)を用いて、下記のようにして、x(t)をxtarと前回の状態xi,k-1との間の点に近づけるための項である。xの値範囲制限はx∈[0,1]である。
Figure JPOXMLDOC01-appb-M000026
including. This term uses ρε(0,1) to approximate x i (t) to the point between x tar and the previous state x i,k−1 as follows: be. The value range limit for x i is x i ε[0,1].
Figure JPOXMLDOC01-appb-M000027
 {A,b}を特定する前に、これらのパラメータの物理的意味を考えて、NOSベースの状態更新DNNアーキテクチャを導出する。
Figure JPOXMLDOC01-appb-M000027
Before specifying {A, b}, we consider the physical meaning of these parameters to derive a NOS-based state update DNN architecture.
 localを、PRS-Netでは式(12)に代入し、DRS-Netでは式(13)に代入することで、図7に示すような、残差、再帰、及び交互の更新ルールは、下記の式(22)のようにまとめられる。 - By substituting V local into equation (12) for PRS-Net and into equation (13) for DRS-Net, the residual, recursive, and alternating update rules as shown in FIG. It is summarized as the following formula (22).
Figure JPOXMLDOC01-appb-M000028
 上記の式において、πはPRS-NETとDRS-NETとで異なる。また、[・]∈[0,1]は、内部要素値を0と1の間の範囲にクランプさせることを示し、
Figure JPOXMLDOC01-appb-M000028
In the above formula, π differs between PRS-NET and DRS-NET. Also, [ ] ∈ [0, 1] indicates that the internal element value is clamped to the range between 0 and 1,
Figure JPOXMLDOC01-appb-M000029
は、負の要素を0にすることを示す。
Figure JPOXMLDOC01-appb-M000029
indicates to set negative elements to 0.
 次に、式(18)における{A,b}の特定について説明する。本実施の形態では、状態ペア{x,x}に対し、衝突なしという制約が課される。この制約のために、{x,x}は、下記の式(23)のように、lmin[m]以上のマンハッタン距離(li|j+lj|i)を保つように制約される。 Next, identification of {A, b} in equation (18) will be described. In this embodiment, no collision constraint is imposed on the state pair {x i , x j }. Because of this constraint, {x i , x j } are constrained to keep the Manhattan distance (l i|j +l j|i ) greater than or equal to l min [m], as in Equation (23) below. be.
Figure JPOXMLDOC01-appb-M000030
 ここで、
Figure JPOXMLDOC01-appb-M000030
here,
Figure JPOXMLDOC01-appb-M000031
は、i番目の車両で計算できる。また、式(23)の左辺を正にするためにマッピングベクトル{omap,i|j,omap,j|i}が選択される。ただし、式(23)を式(18)に示した不等式制約Ax+b≦0の形に変換する際にあいまいさがあるため、{A,b}を一意に決定することができない。
Figure JPOXMLDOC01-appb-M000031
can be calculated for the i-th vehicle. Also, the mapping vectors {oma p,i|j ,o map,j|i } are chosen to make the left hand side of equation (23) positive. However, {A, b} cannot be uniquely determined because there is ambiguity when converting equation (23) into the form of the inequality constraint Ax+b≦0 shown in equation (18).
 式(22)におけるxの更新ルールから、{A,b}は各車両の加速/減速に関連付けられる。例えば、Ai|ji|jが正のときに、i番目の車両は、j番目の車両との間である距離を保つためにブレーキをかける。 From the update rule for x in equation (22), {A,b} is associated with each vehicle's acceleration/deceleration. For example, when A i|j b i|j is positive, the i th vehicle brakes to keep some distance to the j th vehicle.
 後ろの車両が、停滞した前の車両を追い越せないために、多くの車両が停滞するという問題を回避するために、本実施の形態では、各車両ペアに対して、前(front)フラグ/後(back)フラグを割り当て、できるだけ前の車両がブレーキをかけないようにする。具体的には、本実施の形態における{Ai|j,bi|j}の設計は下記の式(24)のとおりである。 To avoid the problem of many vehicles getting stuck because the vehicles behind cannot pass the vehicles ahead that are stuck, in the present embodiment, for each vehicle pair, a front flag/rear (back) flag to prevent the vehicle in front from braking as much as possible. Specifically, the design of {A i|j , b i|j } in this embodiment is as shown in Equation (24) below.
Figure JPOXMLDOC01-appb-M000032
 上記の式において、Ai|jは、σ max=σ min=1として正規化される。
Figure JPOXMLDOC01-appb-M000032
In the above equation, A i|j is normalized as σ 2 max2 min =1.
 上記の式の導出方法、すなわち、不等式形式の衝突なし制約についてより詳細に説明する。現在の状態x、2D方向odir,i、及びパラメータ{smax,Δt}が与えられると、i番目の車両の次の時間ステップの位置は、p=opos,i+Δt・smax・x・odir,iとして推定できる。j番目の車両の位置については、p=opos,j+Δt・smax・x・odir,jとして推定できる。 The derivation of the above equation, ie, the no-collision constraint in inequality form, will now be described in more detail. Given the current state x i , the 2D direction o dir,i , and the parameters {s max ,Δt}, the position of the i-th vehicle's next time step is p i =o pos,i +Δt·s max can be estimated as x i ·o dir,i . For the position of the jth vehicle, it can be estimated as p j =o pos,j +Δt·s max ·x j ·o dir,j .
 マッピングベクトルのペア{omap,i|j,omap,j|i}を選択して、マンハッタン距離を Choose a pair of mapping vectors {o map, i|j , o map, j|i } and calculate the Manhattan distance as
Figure JPOXMLDOC01-appb-M000033
として測定することで、{i,j}車両間のマンハッタン距離をlmin以上に維持する衝突なし制約は、下記の式(25)で与えられる。
Figure JPOXMLDOC01-appb-M000033
A collision-free constraint that keeps the Manhattan distance between {i,j} vehicles greater than or equal to l min is given by equation (25) below.
Figure JPOXMLDOC01-appb-M000034
 上記の式(25)は、式(23)に対応する。
Figure JPOXMLDOC01-appb-M000034
Equation (25) above corresponds to equation (23).
 次に、式(23)の式(24)への変換について説明する。式(22)におけるxの更新ルールから、Ai|ji|jが正のときに、車両iがブレーキをかけることがわかる。前述したとおり、{Ai|j,bi|j}の設計ポリシーは、各車両ペアに前/後フラグを割り当てた後に、後ろの車両の加速/減速を調整することで衝突を回避することである。 Next, conversion of equation (23) to equation (24) will be described. From the update rule for x in equation (22), it can be seen that vehicle i brakes when A i|j b i|j is positive. As mentioned above, the design policy for {A i|j ,b i|j } is to avoid collisions by adjusting the acceleration/deceleration of the vehicle behind after assigning a front/rear flag to each vehicle pair. is.
 追従のケースでは、前/後の割り当ては、車両ペアの位置と方向により決定される。交差点の横断のケースでは、現在の速度と位置を用いて、交差点の中心までの推定残存時間により、前/後フラグの割り当てを決定することができる。 In the follow-up case, the front/rear allocation is determined by the position and orientation of the vehicle pair. In the case of crossing an intersection, the current speed and position can be used to determine the assignment of the front/back flag with the estimated remaining time to the center of the intersection.
 i番目車両が前、j番目車両が後であると仮定すると、式(23)を式(18)の不等式制約に合わせる変換は、式(24)に示すように、後ろの車両の加速/減速を調整するために、Ai|jを1に正規化し、全ての残りのバイアスをbj|iに移すことで行う。{Ai|j,Ai|j}が正規化されたので、AAの全ての固有値は1になる。すなわち、σ max=σ min=1である。 Assuming that the i-th vehicle is in front and the j-th vehicle is in the rear, the transformation of equation (23) to fit the inequality constraints of equation (18) is to accelerate/decelerate the trailing vehicle as shown in equation (24). is done by normalizing A i |j to 1 and transferring all remaining biases to b j |i . Since {A i|j , A i|j } have been normalized, all eigenvalues of A T A become 1. That is, σ 2 max2 min =1.
 PRS-NetとDRS-Netを用いた分散交通整流の手順の概要をアルゴリズム1(Alg.1)として図8に示す。本アルゴリズム1において、各ノード/各エッジの動作が分解して示されている。 An outline of the distributed traffic rectification procedure using PRS-Net and DRS-Net is shown in Figure 8 as Algorithm 1 (Alg.1). In Algorithm 1, the operation of each node/each edge is decomposed and shown.
 図8の手順において、第1行で初期化を行う。第3行~第19行における処理が時刻k毎にkが1からKまで行われる。第4行から第6行において、各ノードiは、制御入力、エッジ接続、及び、式(24)によるパラメータ{Ai|j,bi|j}の取得を行う。 In the procedure of FIG. 8, initialization is performed on the first line. The processing in the 3rd to 19th lines is performed from 1 to K every time k. In lines 4 to 6, each node i performs control input, edge connection, and acquisition of parameters {A i|j , b i|j } according to equation (24).
 第8行~第11行において、各ノードiは、自身に接続するエッジj毎に、メッセージパッシング(メッセージzj|iの受信)を行う。 On lines 8-11, each node i performs message passing (receiving message z j |i ) for each edge j connected to it.
 第13行~第18行において、各ノードは、式(22)に基づく内部状態の更新を行う。これにより、ノードiは、k+1の速度(x)と、k+1のメッセージ(各jのzi|j)を算出することができる。 On lines 13-18, each node updates its internal state based on equation (22). This allows node i to compute k+1 velocities (x i ) and k+1 messages (z i|j for each j).
 上記の処理においては、メッセージパッシングとして、単一次元の{zi|j,zj|i}が、各離散時間において、接続された車両(i,j∈E)間でやりとりされるので、通信は軽量である。 In the above process, as message passing, a single dimensional {z i|j , z j|i } is exchanged between connected vehicles (i, j∈E i ) at each discrete time, so , the communication is lightweight.
 各車両(又は制御サーバ200)は、一定時間の時間ウィンドウKΔt=Tにおけるデータ{x,o,A,b}を記録する。各車両(又は制御サーバ200)は、記録データ{x,o,A,b}用いることにより、逆方向伝搬(11)を行って、θを更新する。順方向伝搬/逆方向伝搬のIラウンドの繰り返しにより、連合ダイナミクス学習が行われる。 Each vehicle (or control server 200) records data {x, o, A, b} in a fixed time window KΔt=T. Each vehicle (or control server 200) performs backward propagation (11) by using the recorded data {x, o, A, b} to update −θ . Federated dynamics learning is performed by iterative I-rounds of forward-propagation/back-propagation.
 図7に示した例は、制御サーバ200が、各離散時間のるデータ{x,o,A,b}を記録して、コスト計算に基づく逆方向伝搬のパラメータ学習を行う場合のイメージを示している。 The example shown in FIG. 7 shows an image in which the control server 200 records data {x, o, A, b} at each discrete time and performs backward propagation parameter learning based on cost calculation. ing.
 (数値実験)
 NOSベースの連合ダイナミクス学習の有効性を示すために、交通シミュレータSUMOを使用して数値実験を行った。車両の衝突を回避しながら平均車両速度
(Numerical experiment)
Numerical experiments were performed using the traffic simulator SUMO to demonstrate the effectiveness of NOS-based associative dynamics learning. average vehicle speed while avoiding vehicle collisions
Figure JPOXMLDOC01-appb-M000035
がxtar=1.0に近づくようにθの学習を行うことを目的とした。最大速度をsmax=8.75[m/s](=31.5km/h)とした。代表的なパラメータは図9に示すとおりである。
Figure JPOXMLDOC01-appb-M000035
We aimed to train - θ so that ≉x tar =1.0. The maximum speed was s max =8.75 [m/s] (=31.5 km/h). Typical parameters are shown in FIG.
 <実験のセッティング>
 図10に示すように、N=30台の車両を交通シミュレータにランダムに配置した。また、10個の道路マップを用意した。学習データへのオーバーフィッティングを避けるために、各道路マップは、直線道路の長さと交差点の位置に対して小さなランダム摂動を有する。
<Experiment setting>
As shown in FIG. 10, N=30 vehicles were randomly placed in the traffic simulator. In addition, 10 road maps were prepared. To avoid overfitting to the training data, each road map has small random perturbations for straight road lengths and intersection locations.
 車両の初期状態(位置と速度)をランダムに設定した。各車両は、右折と左折により事前に定義されたランダムに選択された道路を走行した。(ランダムな道路マップと道路摂動を有する)各ミニバッチに対し、K=300[回]及びΔt=0.1[s]を選択した。 The vehicle's initial state (position and speed) was set randomly. Each vehicle traveled on a randomly selected road pre-defined with right and left turns. For each mini-batch (with random road maps and road perturbations), we chose K=300 [times] and Δt=0.1 [s].
 したがって、交通シミュレーションによる順方向伝搬は、T=KΔt=30.0秒行われ、続いて、記録されたデータ{x,o,A,b}を用いて、ダイナミクスパラメータθの更新のために逆方向伝搬が行われた。パラメータは、学習レート0.0025でgθを用いてAdamで更新した。この順方向伝搬と逆方向伝搬の1つのセットが1ラウンドである。 Therefore, the forward propagation by the traffic simulation is performed for T = KΔt = 30.0 seconds and then using the recorded data {x, o, A, b} to update the dynamics parameter Back propagation was performed. Parameters were updated with Adam using g θ with a learning rate of 0.0025. One set of this forward propagation and backward propagation is one round.
 ダイナミクスパラメータの推定値は、合計I=500ラウンドにわたって得られた。評価セッションは10ラウンド毎に実施した。提案方法と参照方法の公平な比較のために、合計50パターンの固定初期設定(10道路マップ×5道路ランダム性)を用意した。  Dynamics parameter estimates were obtained over a total of I = 500 rounds. Evaluation sessions were conducted every 10 rounds. A total of 50 patterns of fixed initial settings (10 road maps x 5 road randomness) were prepared for a fair comparison between the proposed method and the reference method.
 各車両の加速/減速を決定するための制御入力として、各車両とその周囲の画像oimg,iが、各離散時間インスタントで生成された。 An image o img,i of each vehicle and its surroundings was generated at each discrete time instant as the control input for determining the acceleration/deceleration of each vehicle.
 画像のサイズは64(W)×64(H)×5(Ch)として定められる。各チャネルは、(1)周囲の道路、(2)周囲の車両位置、(3)それらの正規化速度、及び(4、5)周囲の車両の2D方向ベクトルからなる。各画像は、各車両が同じ方向を向くように回転させられている。図10における1の車両と30の車両のoimgの例をそれぞれ、図11と図12に示す。また、図13に、状態更新と学習をラウンド毎に繰り返すイメージを示す。 The size of the image is defined as 64 (W) x 64 (H) x 5 (Ch). Each channel consists of (1) the surrounding roads, (2) the surrounding vehicle positions, (3) their normalized velocities, and (4,5) the 2D direction vectors of the surrounding vehicles. Each image is rotated so that each vehicle is facing the same direction. Examples of o img for vehicle 1 and vehicle 30 in FIG. 10 are shown in FIGS. 11 and 12, respectively. FIG. 13 shows an image of repeating state update and learning for each round.
 提案方法(NOS)において、PRS‐NetおよびDRS-NetをAlg.1に基づいて構築した。式(22)の状態の更新では、  In the proposed method (NOS), PRS-Net and DRS-Net are set to Alg. 1. In updating the state of equation (22),
Figure JPOXMLDOC01-appb-M000036
において、小サイズのCNNを使用し、xにおける急激な変化を緩和するためにα=0.05、ρ=0.75を選択した。最適な離散時間間隔の設定として、Δt=2πασ min=0.1π[s]を使用した。PRS-Netに対してπ=1とし、DRS-Netに対してπ=1/2とするので、PRS-NetとDRS-Netとで、T=KΔt=2πKασ minで表される順方向/逆方向伝搬の秒数は異なる。
Figure JPOXMLDOC01-appb-M000036
, we used a small-sized CNN and chose α=0.05, ρ=0.75 to mitigate abrupt changes in x i . Δt=2πασ 2 min =0.1π[s] was used as the optimal discrete time interval setting. Since π=1 for PRS-Net and π=1/2 for DRS-Net, the forward direction/ The number of seconds for backward propagation is different.
 現実的なメッセージパッシングを実現するために、Pは疎な行列であると仮定した。lcom=25.0[m]のマンハッタン距離内の車両ペア(i,j∈E)間の通信をいつでも行ってよいようにした。つまり、通信エリアを25.0[m]とした。{i,j}の車両間の通信が開始された後、{zi|j,Ai|j,bi|j}はi番目の車両に適応的に割り当てられた。 To achieve realistic message passing, we assumed P to be a sparse matrix. We allowed communication between vehicle pairs (i, jεE i ) within Manhattan distance of l com =25.0 [m] at any time. That is, the communication area was set to 25.0 [m]. {z i|j , A i|j , b i|j } were adaptively assigned to the i-th vehicle after communication between {i,j} vehicles was initiated.
 エッジにより接続された車両がlcomより離れるか、又は、道路が変化(例えば、交差点から直線道路に変化)すると、メッセージパッシングは停止し、メモリを節約するために変数の割り当てが解除される。式(23)の最小距離制約としてlmin=15.0[m]を用いた。 When a vehicle connected by an edge is further than l_com or the road changes (eg, from an intersection to a straight road), message passing stops and variables are deallocated to save memory. l min =15.0 [m] was used as the minimum distance constraint in Equation (23).
 <参照方法>
 離散化ODE(2)に基づく理論的DNNアーキテクチャであるNOSを評価するために、3つの参照システムを用意した。
<Reference method>
Three reference systems were prepared to evaluate NOS, a theoretical DNN architecture based on discretized ODE(2).
 第1の参照システムとして、適切なパラメータ設定(TraCIの速度モード:31)を有するSUMOのネイティブ衝突フリー交通整流を使用した。しかし、SUMOは集中化された交通信号を用いて制御するように設計されていると考えられ、衝突を避けるために交差点に入る前にSUMO制御車両はしばしば停止した。 As the first reference system, we used SUMO's native collision-free traffic rectification with appropriate parameter settings (TraCI's speed mode: 31). However, SUMO was thought to be designed to be controlled using centralized traffic lights, and SUMO-controlled vehicles often stopped before entering intersections to avoid collisions.
 このSUMOの衝突フリー設定の下でのこの状況を改善するために、第2の参照システムとしてプラグアンドプレイ(PnP)Netを構築した。PnP-Netでは、xの更新のために再帰DNNで実装された状態遷移を使用している。この方法では、可能な限り分析的な導出を避け、データ駆動方式で学習した。このPnP-NetのDNNパラメータサイズは、最初はNOSのパラメータの値にできるだけ近い値に設定された。 To remedy this situation under this SUMO collision-free setting, we built Plug and Play (PnP) Net as a second reference system. PnP-Net uses state transitions implemented in recursive DNNs for updating x. The method avoided analytical derivation as much as possible and learned in a data-driven manner. The DNN parameter sizes of this PnP-Net were initially set as close as possible to the NOS parameter values.
 第3の参照システムとして、PRS-NetとDRS-Netの両方の種類において、学習可能なDNN関数  As a third reference system, in both the PRS-Net and DRS-Net types, learnable DNN functions
Figure JPOXMLDOC01-appb-M000037
を使用しないNOSを用いた。PnP-Net、学習不可のNOSともに、図7に示すように、(i)内部状態更新、(ii)近接車両間のメッセージパッシングが交互に行われている。
Figure JPOXMLDOC01-appb-M000037
NOS was used without . As shown in FIG. 7, both PnP-Net and learning-impossible NOS alternately perform (i) internal state update and (ii) message passing between adjacent vehicles.
 <実装>
 CPU(AMD EPYC 7262 8-Core 4)を有する、GPU(NVIDIA DGX A100 8)を持つサーバ上で動作するソフトウェアを構築した。DNNにはPyTorch(1.9.0+cu111)を用いた。PRS-Netの各ラウンドにおいて、平均計算時間は、SUMO-GUIを考慮しない場合、45.4[s]であった。
<Implementation>
We built the software running on a server with a GPU (NVIDIA DGX A100 8), with a CPU (AMD EPYC 7262 8-Core 4). PyTorch (1.9.0+cu111) was used for DNN. In each round of PRS-Net, the average computation time was 45.4 [s] without considering SUMO-GUI.
 <実験結果>
 図14に実験結果を示す。図14は、平均正規化速度がラウンド数の増加に伴って変化することを示している。最高速度(av=0.98)はPRS-Netで得られ、2番目の速度(av=0.97)がDRS-Netで得られた。これらの間の性能差はわずかである。すなわち、両方の方法はNOSに基づく連合ダイナミクス学習に有効である。いずれの学習ラウンドにおいても、可能な限り車間距離を維持するようにθが更新されたことを確認した。
<Experimental results>
FIG. 14 shows the experimental results. FIG. 14 shows that the average normalized speed changes with increasing number of rounds. The highest speed ( −x av =0.98) was obtained with the PRS-Net and the second speed ( −x av =0.97) with the DRS-Net. The performance difference between them is small. That is, both methods are effective for NOS-based associative dynamics learning. In each learning round, we confirmed that was updated to maintain the inter-vehicle distance as much as possible.
 参照方法のうち、PnP-Netが最も高い速度(av=0.64)を得た。しかし、距離を保つための追加コストが、所望のダイナミクスを得るための訓練に干渉したため、NOSのスコアには達することができなかった。 Among the reference methods, PnP-Net obtained the highest speed ( −x av =0.64). However, NOS scores could not be reached because the added cost of keeping distance interfered with training to obtain the desired dynamics.
 残りの学習不可の参照方法では、衝突を避けるために交差点に入る前に車両が停止することが多く、平均正規化速度は、学習不可PRS-Netで0.30、学習不可DRS-Netで0.31、SUMOのネイティブ交通整流システムで0.56であった。実験結果により、NOSに基づく連合ダイナミクス学習が有効であることがわかった。 For the remaining non-learnable reference methods, where the vehicle often stops before entering the intersection to avoid a collision, the average normalized speed is 0.30 for non-learnable PRS-Net and 0 for non-learnable DRS-Net. .31, and 0.56 with SUMO's native traffic control system. Experimental results show that NOS-based associative dynamics learning is effective.
 図15は、NOSに基づく連合ダイナミクス学習(Proposed method)とSUMO実装の従来法(conventional method)の相違をより分かり易く示した図である。図15に示すように、提案法は学習とともに正規化速度が目標値に近づき、従来法(SUMO実装)よりも大幅に速度が向上する。 FIG. 15 is a diagram that more clearly shows the difference between NOS-based joint dynamics learning (proposed method) and the conventional method of SUMO implementation (conventional method). As shown in FIG. 15, in the proposed method, the normalization speed approaches the target value as learning progresses, and the speed is greatly improved over the conventional method (SUMO implementation).
 また、図16は、評価セットに対する収束曲線を示し、0.0に近づくほど良い性能であることを示す。図16に示すとおり、学習とともにロス値(正規化速度の目標値と現在値の差に比例)が下がることが示されている。 Also, FIG. 16 shows a convergence curve for the evaluation set, showing better performance as it approaches 0.0. As shown in FIG. 16, the loss value (proportional to the difference between the normalized speed target value and the current value) decreases with learning.
 (装置構成例)
 図17に、車両1の構成例を示す。図17に示すように、車両1は、カメラ11、センサ12、制御装置100、通信部13、及び駆動部14を有する。カメラ11は、周囲の画像を取得する。センサ12は、例えば、LidarやGPS等により自身の位置情報を取得する。センサ12は、自身の速度を取得する機能を含んでもよい。また、これら以外の情報を更に取得するセンサが搭載されてもよい。
(Device configuration example)
FIG. 17 shows a configuration example of the vehicle 1. As shown in FIG. As shown in FIG. 17, the vehicle 1 has a camera 11, a sensor 12, a control device 100, a communication section 13, and a drive section . Camera 11 acquires an image of the surroundings. The sensor 12 acquires its own position information by Lidar, GPS, or the like, for example. Sensor 12 may include the ability to acquire its own velocity. Also, a sensor that further acquires information other than these may be mounted.
 制御装置100は、カメラ11及びセンサ12により取得された外部の情報を入力し、アルゴリズム1の処理を行って、状態(速度)x、及びメッセージzを出力する。また、制御装置100は、式(11)に基づく逆方向伝搬によるパラメータ学習の機能を含んでもよい。 The control device 100 inputs external information acquired by the camera 11 and the sensor 12, performs the processing of Algorithm 1, and outputs the state (speed) x and the message z. The control device 100 may also include a function of parameter learning by backward propagation based on Equation (11).
 通信部13は、隣接する他の車両から送信されたメッセージを受信して、当該メッセージを制御装置100に渡すとともに、制御装置100から出力されたメッセージを隣接する他の車両へ送信する。また、制御サーバ200で学習を行う場合において、通信部13は、状態更新において得られた記録データ{x,o,A,b}を制御サーバ200に送信するとともに、最新の学習済みパラメータθを制御サーバ200から受信する。 The communication unit 13 receives a message transmitted from another adjacent vehicle, passes the message to the control device 100, and transmits a message output from the control device 100 to the other adjacent vehicle. In addition, when learning is performed by the control server 200, the communication unit 13 transmits the recorded data {x, o, A, b} obtained in the state update to the control server 200, and the latest learned parameter θ Received from control server 200 .
 駆動部14は、制御装置100から出力される状態xに従って、走行を行う機能(エンジン、モータ等)を含む。例えば、制御装置100から状態として、ある速度が出力された場合、その速度で走行を行うように駆動を実施する。 The drive unit 14 includes a function (engine, motor, etc.) for running according to the state x output from the control device 100 . For example, when a certain speed is output as a state from the control device 100, the vehicle is driven so as to run at that speed.
 図18に、制御装置100の構成例を示す。図18に示すように、制御装置100は、入力部110、状態更新部120、出力部130、データ格納部140、学習部150を備える。なお、制御サーバ200で学習を行う場合には、制御装置100において学習部150を備えないこととしてもよい。 18 shows a configuration example of the control device 100. FIG. As shown in FIG. 18 , the control device 100 includes an input section 110 , a state update section 120 , an output section 130 , a data storage section 140 and a learning section 150 . Note that when learning is performed by the control server 200 , the learning unit 150 may not be provided in the control device 100 .
 入力部110は、カメラ11やセンサ12により取得した外部情報o、及び、隣接車両から受信したメッセージzを入力する。状態更新部120は、アルゴリズム1に従って、xとzの状態更新を行うNOSを実現するDNNである。 The input unit 110 inputs external information o acquired by the camera 11 and the sensor 12 and a message z received from an adjacent vehicle. The state update unit 120 is a DNN that implements a NOS that updates the states of x and z according to Algorithm 1 .
 出力部130は、状態更新部120により得られた状態xとメッセージzを出力する。データ格納部140は、状態更新部120による処理過程で得られたデータ{x,o,A,b}を、離散時間毎に記録する。また、データ格納部140は、最新の学習済みパラメータθを格納し、状態更新部120は、当該最新の学習済みパラメータθを用いて状態更新処理を実行する。 The output unit 130 outputs the state x obtained by the state update unit 120 and the message z. The data storage unit 140 records the data {x, o, A, b} obtained in the process of processing by the state update unit 120 for each discrete time. Further, the data storage unit 140 stores the latest learned parameter θ, and the state update unit 120 executes state update processing using the latest learned parameter θ.
 学習部150は、記録データ{x,o,A,b}を用いて逆方向伝搬(11)によりパラメータθの学習を行い、学習済みパラメータθをデータ格納部140に格納する。 The learning unit 150 learns the parameter θ by backward propagation (11) using the recorded data {x, o, A, b}, and stores the learned parameter θ in the data storage unit 140.
 図19に、制御サーバ200の構成例を示す。図19に示すように、制御サーバ200は、入力部210、学習部220、出力部230、データ格納部240を備える。 FIG. 19 shows a configuration example of the control server 200. As shown in FIG. 19, the control server 200 includes an input unit 210, a learning unit 220, an output unit 230, and a data storage unit 240.
 入力部210は、各車両から記録データ{x,o,A,b}を受信する。データ格納部240は、各車両から受信した記録データ{x,o,A,b}を格納する。学習部220は、データ格納部240に格納された記録データ{x,o,A,b}を用いて逆方向伝搬(11)によりパラメータθの学習を行う。出力部230は、学習済みのパラメータθを各車両に送信する。 The input unit 210 receives recorded data {x, o, A, b} from each vehicle. The data storage unit 240 stores recorded data {x, o, A, b} received from each vehicle. The learning unit 220 learns the parameter θ by backward propagation (11) using the recorded data {x, o, A, b} stored in the data storage unit 240 . The output unit 230 transmits the learned parameter θ to each vehicle.
 (ハードウェア構成例)
 制御装置100及び制御サーバ200はいずれも、例えば、コンピュータにプログラムを実行させることにより実現できる。
(Hardware configuration example)
Both the control device 100 and the control server 200 can be realized, for example, by causing a computer to execute a program.
 すなわち、当該装置は、コンピュータに内蔵されるCPU、GPUやメモリ等のハードウェア資源を用いて、当該装置で実施される処理に対応するプログラムを実行することによって実現することが可能である。上記プログラムは、コンピュータが読み取り可能な記録媒体(可搬メモリ等)に記録して、保存したり、配布したりすることが可能である。また、上記プログラムをインターネットや電子メール等、ネットワークを通して提供することも可能である。 That is, the device can be realized by executing a program corresponding to the processing performed by the device using hardware resources such as a CPU, GPU, and memory built into the computer. The above program can be recorded in a computer-readable recording medium (portable memory, etc.), saved, or distributed. It is also possible to provide the above program through a network such as the Internet or e-mail.
 図20は、上記コンピュータのハードウェア構成例を示す図である。図20のコンピュータは、それぞれバスBSで相互に接続されているドライブ装置1000、補助記憶装置1002、メモリ装置1003、プロセッサ1004、インタフェース装置1005、表示装置1006、入力装置1007、出力装置1008等を有する。プロセッサ1004は、CPUであってもよいし、GPUであってもよいし、CPUとGPUであってもよい。 FIG. 20 is a diagram showing a hardware configuration example of the computer. The computer of FIG. 20 has a drive device 1000, an auxiliary storage device 1002, a memory device 1003, a processor 1004, an interface device 1005, a display device 1006, an input device 1007, an output device 1008, etc., which are interconnected by a bus BS. . The processor 1004 may be a CPU, a GPU, or both a CPU and a GPU.
 当該コンピュータでの処理を実現するプログラムは、例えば、CD-ROM又はメモリカード等の記録媒体1001によって提供される。プログラムを記憶した記録媒体1001がドライブ装置1000にセットされると、プログラムが記録媒体1001からドライブ装置1000を介して補助記憶装置1002にインストールされる。但し、プログラムのインストールは必ずしも記録媒体1001より行う必要はなく、ネットワークを介して他のコンピュータよりダウンロードするようにしてもよい。補助記憶装置1002は、インストールされたプログラムを格納すると共に、必要なファイルやデータ等を格納する。 A program that implements the processing in the computer is provided by a recording medium 1001 such as a CD-ROM or memory card, for example. When the recording medium 1001 storing the program is set in the drive device 1000 , the program is installed from the recording medium 1001 to the auxiliary storage device 1002 via the drive device 1000 . However, the program does not necessarily need to be installed from the recording medium 1001, and may be downloaded from another computer via the network. The auxiliary storage device 1002 stores installed programs, as well as necessary files and data.
 メモリ装置1003は、プログラムの起動指示があった場合に、補助記憶装置1002からプログラムを読み出して格納する。プロセッサ1004は、メモリ装置1003に格納されたプログラムに従って、ライトタッチ維持装置100に係る機能を実現する。インタフェース装置1005は、ネットワーク等に接続するためのインタフェースとして用いられる。表示装置1006はプログラムによるGUI(Graphical User Interface)等を表示する。入力装置1007はキーボード及びマウス、ボタン、又はタッチパネル等で構成され、様々な操作指示を入力させるために用いられる。出力装置1008は演算結果を出力する。 The memory device 1003 reads and stores the program from the auxiliary storage device 1002 when a program activation instruction is received. The processor 1004 implements the functions of the light touch maintaining device 100 according to programs stored in the memory device 1003 . The interface device 1005 is used as an interface for connecting to a network or the like. A display device 1006 displays a GUI (Graphical User Interface) or the like by a program. An input device 1007 is composed of a keyboard, a mouse, buttons, a touch panel, or the like, and is used to input various operational instructions. The output device 1008 outputs the calculation result.
 (まとめ、効果)
 以上説明したとおり、本実施の形態では、連合ダイナミクス学習のためのNODEの拡張としてNOSを提案し、式(2)の2つのサブダイナミクスを、(i)内部状態更新と(ii)メッセージパッシングに割り当てることとした。また、作用素分解法に基づく式(2)の離散化を通して、PRS‐NetおよびDRS‐NetのようなNOSベースDNNアーキテクチャを構築した。
(Summary, effect)
As described above, in this embodiment, NOS is proposed as an extension of NODE for federated dynamics learning, and the two subdynamics of equation (2) are applied to (i) internal state updating and (ii) message passing. decided to assign. We also constructed NOS-based DNN architectures such as PRS-Net and DRS-Net through the discretization of equation (2) based on the operator decomposition method.
 また、NOSを、目標値までの平均速度を最大化するダイナミクスパラメータθを見つけることを目的とする信号フリー交通整流の問題に適用し、効果が得られた。 NOS has also been successfully applied to the problem of signal-free traffic rectification with the goal of finding the dynamics parameter that maximizes the average speed to a target value.
 これにより、信号を使用することなく、交通事故(衝突)を抑止しつつ、移動・輸送時間を限界まで短縮することが期待できる。 As a result, it can be expected to reduce travel and transportation time to the limit while preventing traffic accidents (collisions) without using traffic lights.
 (付記)
 本明細書には、少なくとも下記各項の交通整流システム、制御装置、制御方法、及びプログラムが開示されている。
(第1項)
 制御装置を備える移動体を複数台備え、当該複数台の移動体が自律的に、移動体間の衝突を抑止するように交通整流を実施する交通整流システムにおける前記制御装置であって、
 前記移動体の状態更新のためのサブダイナミクスと、前記移動体に近接する他の移動体との間で行われるメッセージパッシングのためのサブダイナミクスとを有する状態更新ダイナミクスに基づいて、移動体間の衝突を抑止するための制約下で、前記移動体の状態を更新する状態更新部と、
 前記状態更新部により更新された状態と、メッセージとを出力する出力部と、
 を備える制御装置。
(第2項)
 前記状態更新部は、ニューラルネットワークを用いて、前記移動体の状態更新と、前記メッセージパッシングを交互に繰り返す処理を実行する
 第1項に記載の制御装置。
(第3項)
 前記ニューラルネットワークにおけるパラメータは、前記制約下で移動体の速度が目標速度に近づくように、随伴法に基づく逆伝搬計算により更新される
 第2項に記載の制御装置。
(第4項)
 前記状態更新部は、ある時点での状態と、当該時点での外部制御入力と、当該時点で他の移動体から受信したメッセージとに基づいて、次の時点の状態を算出する
 第1項ないし第3項のうちいずれか1項に記載の制御装置。
(第5項)
 前記制約は、前記外部制御入力に基づいて算出される、前記移動体と前記他の移動体との間の距離を予め定めた距離以上とすることである
 第4項に記載の制御装置。
(第6項)
 第1項ないし第5項のうちいずれか1項に記載の制御装置を備える複数台の移動体と、
 前記状態更新部が備えるニューラルネットワークのパラメータを、前記制約下で複数台の移動体の平均速度が目標速度に近づくように、随伴法に基づく逆伝搬計算により更新する制御サーバと
 を備える交通整流システム。
(第7項)
 制御装置を備える移動体を複数台備え、当該複数台の移動体が自律的に、移動体間の衝突を抑止するように交通整流を実施する交通整流システムにおける前記制御装置が実行する制御方法であって、
 前記移動体の状態更新のためのサブダイナミクスと、前記移動体に近接する他の移動体との間で行われるメッセージパッシングのためのサブダイナミクスとを有する状態更新ダイナミクスに基づいて、移動体間の衝突を抑止するための制約下で、前記移動体の状態を更新する状態更新ステップと、
 前記状態更新ステップにより更新された状態と、メッセージとを出力する出力ステップと、
 を備える制御方法。
(第8項)
 コンピュータを、第1項ないし第5項のうちいずれか1項に記載の制御装置における各部として機能させるためのプログラム。
(Appendix)
This specification discloses at least a traffic control system, a control device, a control method, and a program for each of the following items.
(Section 1)
A control device in a traffic rectification system comprising a plurality of mobile bodies equipped with a control device, wherein the plurality of mobile bodies autonomously rectify traffic so as to prevent collisions between the mobile bodies,
Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state updating unit that updates the state of the moving object under constraints for deterring collisions;
an output unit that outputs the state updated by the state update unit and a message;
A control device comprising:
(Section 2)
2. The control device according to claim 1, wherein the state update unit uses a neural network to alternately repeat the state update of the moving object and the message passing.
(Section 3)
3. The control device according to claim 2, wherein the parameters in the neural network are updated by backpropagation calculation based on the adjoint method so that the speed of the moving object approaches the target speed under the constraint.
(Section 4)
The state update unit calculates the state at the next point in time based on the state at the point in time, the external control input at the point in time, and the message received from another mobile object at the point in time. 4. The control device according to any one of items 3 to 3.
(Section 5)
5. The control device according to claim 4, wherein the restriction is to set the distance between the mobile body and the other mobile body to a predetermined distance or more, which is calculated based on the external control input.
(Section 6)
a plurality of mobile bodies equipped with the control device according to any one of items 1 to 5;
a control server that updates the parameters of the neural network provided in the state update unit by back propagation calculation based on the adjoint method so that the average speed of a plurality of moving bodies approaches a target speed under the constraints. .
(Section 7)
A control method executed by a control device in a traffic control system comprising a plurality of mobile bodies equipped with a control device and autonomously controlling traffic so as to prevent collisions between the mobile bodies. There is
Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state update step of updating the state of the moving object under constraints for deterring collisions;
an output step of outputting the state updated by the state update step and a message;
A control method comprising:
(Section 8)
A program for causing a computer to function as each unit in the control device according to any one of items 1 to 5.
 以上、本実施の形態について説明したが、本発明はかかる特定の実施形態に限定されるものではなく、特許請求の範囲に記載された本発明の要旨の範囲内において、種々の変形・変更が可能である。 Although the present embodiment has been described above, the present invention is not limited to such a specific embodiment, and various modifications and changes can be made within the scope of the gist of the present invention described in the claims. It is possible.
1 車両
11 カメラ
12 センサ
13 通信部
14 駆動部
100 制御装置
110 入力部
120 状態更新部
130 出力部
140 データ格納部
150 学習部
200 制御サーバ
210 入力部
220 学習部
230 出力部
240 データ格納部
300 ネットワーク
1000 ドライブ装置
1001 記録媒体
1002 補助記憶装置
1003 メモリ装置
1004 プロセッサ
1005 インタフェース装置
1006 表示装置
1007 入力装置
1 vehicle 11 camera 12 sensor 13 communication unit 14 drive unit 100 control device 110 input unit 120 state update unit 130 output unit 140 data storage unit 150 learning unit 200 control server 210 input unit 220 learning unit 230 output unit 240 data storage unit 300 network 1000 drive device 1001 recording medium 1002 auxiliary storage device 1003 memory device 1004 processor 1005 interface device 1006 display device 1007 input device

Claims (8)

  1.  制御装置を備える移動体を複数台備え、当該複数台の移動体が自律的に、移動体間の衝突を抑止するように交通整流を実施する交通整流システムにおける前記制御装置であって、
     前記移動体の状態更新のためのサブダイナミクスと、前記移動体に近接する他の移動体との間で行われるメッセージパッシングのためのサブダイナミクスとを有する状態更新ダイナミクスに基づいて、移動体間の衝突を抑止するための制約下で、前記移動体の状態を更新する状態更新部と、
     前記状態更新部により更新された状態と、メッセージとを出力する出力部と、
     を備える制御装置。
    A control device in a traffic rectification system comprising a plurality of mobile bodies equipped with a control device, wherein the plurality of mobile bodies autonomously rectify traffic so as to prevent collisions between the mobile bodies,
    Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state updating unit that updates the state of the moving object under constraints for deterring collisions;
    an output unit that outputs the state updated by the state update unit and a message;
    A control device comprising:
  2.  前記状態更新部は、ニューラルネットワークを用いて、前記移動体の状態更新と、前記メッセージパッシングを交互に繰り返す処理を実行する
     請求項1に記載の制御装置。
    The control device according to claim 1, wherein the state update unit uses a neural network to alternately repeat the state update of the moving body and the message passing.
  3.  前記ニューラルネットワークにおけるパラメータは、前記制約下で移動体の速度が目標速度に近づくように、随伴法に基づく逆伝搬計算により更新される
     請求項2に記載の制御装置。
    3. The control device according to claim 2, wherein the parameters in the neural network are updated by backpropagation calculation based on the adjoint method so that the speed of the moving body approaches the target speed under the constraint.
  4.  前記状態更新部は、ある時点での状態と、当該時点での外部制御入力と、当該時点で他の移動体から受信したメッセージとに基づいて、次の時点の状態を算出する
     請求項1ないし3のうちいずれか1項に記載の制御装置。
    The state update unit calculates the state at the next point in time based on the state at the point in time, the external control input at the point in time, and the message received from another mobile object at the point in time. 4. The control device according to any one of 3.
  5.  前記制約は、前記外部制御入力に基づいて算出される、前記移動体と前記他の移動体との間の距離を予め定めた距離以上とすることである
     請求項4に記載の制御装置。
    5. The control device according to claim 4, wherein the restriction is that the distance between the moving body and the other moving body, which is calculated based on the external control input, is greater than or equal to a predetermined distance.
  6.  請求項1ないし5のうちいずれか1項に記載の制御装置を備える複数台の移動体と、
     前記状態更新部が備えるニューラルネットワークのパラメータを、前記制約下で複数台の移動体の平均速度が目標速度に近づくように、随伴法に基づく逆伝搬計算により更新する制御サーバと
     を備える交通整流システム。
    a plurality of moving bodies comprising the control device according to any one of claims 1 to 5;
    a control server that updates the parameters of the neural network provided in the state update unit by back propagation calculation based on the adjoint method so that the average speed of a plurality of moving bodies approaches a target speed under the constraints. .
  7.  制御装置を備える移動体を複数台備え、当該複数台の移動体が自律的に、移動体間の衝突を抑止するように交通整流を実施する交通整流システムにおける前記制御装置が実行する制御方法であって、
     前記移動体の状態更新のためのサブダイナミクスと、前記移動体に近接する他の移動体との間で行われるメッセージパッシングのためのサブダイナミクスとを有する状態更新ダイナミクスに基づいて、移動体間の衝突を抑止するための制約下で、前記移動体の状態を更新する状態更新ステップと、
     前記状態更新ステップにより更新された状態と、メッセージとを出力する出力ステップと、
     を備える制御方法。
    A control method executed by a control device in a traffic control system comprising a plurality of mobile bodies equipped with a control device and autonomously controlling traffic so as to prevent collisions between the mobile bodies. There is
    Between mobiles based on state update dynamics, including sub-dynamics for state updates of said mobile and sub-dynamics for message passing between other mobiles in proximity to said mobile. a state update step of updating the state of the moving body under constraints for deterring collisions;
    an output step of outputting the state updated by the state update step and a message;
    A control method comprising:
  8.  コンピュータを、請求項1ないし5のうちいずれか1項に記載の制御装置における各部として機能させるためのプログラム。 A program for causing a computer to function as each unit in the control device according to any one of claims 1 to 5.
PCT/JP2021/040810 2021-11-05 2021-11-05 Control device, traffic rectification system, control method, and program WO2023079690A1 (en)

Priority Applications (2)

Application Number Priority Date Filing Date Title
PCT/JP2021/040810 WO2023079690A1 (en) 2021-11-05 2021-11-05 Control device, traffic rectification system, control method, and program
JP2023557546A JPWO2023079690A1 (en) 2021-11-05 2021-11-05

Applications Claiming Priority (1)

Application Number Priority Date Filing Date Title
PCT/JP2021/040810 WO2023079690A1 (en) 2021-11-05 2021-11-05 Control device, traffic rectification system, control method, and program

Publications (1)

Publication Number Publication Date
WO2023079690A1 true WO2023079690A1 (en) 2023-05-11

Family

ID=86240905

Family Applications (1)

Application Number Title Priority Date Filing Date
PCT/JP2021/040810 WO2023079690A1 (en) 2021-11-05 2021-11-05 Control device, traffic rectification system, control method, and program

Country Status (2)

Country Link
JP (1) JPWO2023079690A1 (en)
WO (1) WO2023079690A1 (en)

Citations (2)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
JP2010176353A (en) * 2009-01-29 2010-08-12 Toyota Motor Corp Control system for traveling in column
JP2019155949A (en) * 2018-03-07 2019-09-19 ワブコジャパン株式会社 Rank travel method and vehicle

Patent Citations (2)

* Cited by examiner, † Cited by third party
Publication number Priority date Publication date Assignee Title
JP2010176353A (en) * 2009-01-29 2010-08-12 Toyota Motor Corp Control system for traveling in column
JP2019155949A (en) * 2018-03-07 2019-09-19 ワブコジャパン株式会社 Rank travel method and vehicle

Also Published As

Publication number Publication date
JPWO2023079690A1 (en) 2023-05-11

Similar Documents

Publication Publication Date Title
Zhu et al. A survey of deep rl and il for autonomous driving policy learning
Huegle et al. Dynamic input for deep reinforcement learning in autonomous driving
Havlak et al. Discrete and continuous, probabilistic anticipation for autonomous robots in urban environments
Chen et al. Fastrack: a modular framework for real-time motion planning and guaranteed safe tracking
Gidado et al. A survey on deep learning for steering angle prediction in autonomous vehicles
Garrido et al. Robot formation motion planning using fast marching
Xu et al. Two-layer distributed hybrid affine formation control of networked Euler–Lagrange systems
Zhao et al. Combined longitudinal and lateral control for heterogeneous nodes in mixed vehicle platoon under V2I communication
Xu et al. Heuristic and random search algorithm in optimization of route planning for Robot’s geomagnetic navigation
Liu et al. Heuristics‐oriented overtaking decision making for autonomous vehicles using reinforcement learning
Németh et al. Optimal control of overtaking maneuver for intelligent vehicles
Song et al. Multi-vehicle tracking with microscopic traffic flow model-based particle filtering
Liu et al. A new path plan method based on hybrid algorithm of reinforcement learning and particle swarm optimization
Eilers et al. Learning the human longitudinal control behavior with a modular hierarchical bayesian mixture-of-behaviors model
Youssef et al. Comparative study of end-to-end deep learning methods for self-driving car
Banerjee et al. A survey on physics informed reinforcement learning: Review and open problems
WO2023079690A1 (en) Control device, traffic rectification system, control method, and program
Sun et al. Feedback enhanced motion planning for autonomous vehicles
Wang et al. Safe Reinforcement Learning for Automated Vehicles via Online Reachability Analysis
Vikas et al. Multi-robot path planning using a hybrid dynamic window approach and modified chaotic neural oscillator-based hyperbolic gravitational search algorithm in a complex terrain
Maheshwari et al. PIAug--Physics Informed Augmentation for Learning Vehicle Dynamics for Off-Road Navigation
He et al. Trustworthy autonomous driving via defense-aware robust reinforcement learning against worst-case observational perturbations
Choi et al. Density matching reward learning
COVACIU Development of a virtual reality simulator for an autonomous vehicle
Xidias A decision algorithm for motion planning of car-like robots in dynamic environments

Legal Events

Date Code Title Description
121 Ep: the epo has been informed by wipo that ep was designated in this application

Ref document number: 21963285

Country of ref document: EP

Kind code of ref document: A1

WWE Wipo information: entry into national phase

Ref document number: 2023557546

Country of ref document: JP