Oracle Motion Cueing Algorithm#
The demo_oracle_predictor
application demonstrates the integration of an "Oracle" predictor and the controller using the Pipeline.
That is, the pipeline
namespace contains a number of InOutput
and Step
classes that, when used together:
- can be used to calculate a prediction (output reference),
- communicate that to the controller,
- retrieve the control commands to be sent to the simulator, and
- deal with potential computational overruns of the iterative solver in the controller.
Some of the InOutput
and Step
types used in this example are class templates taking the simulator class as argument. To use these InOutput
and Step
types, they need to be instantiated explicitly somewhere in the program using them. This page documents how.
This example uses the MpmcaHexapod
simulator and thus links against the mpmca_hexapod::mpmca_hexapod
target, see the CMakeLists.txt
in the application folder.
Requires a dataset download
This example requires you to download data from an external source. The required datasets are quite large, so you might want to start the download first. See the section below.
Configuration files
In this example, the Pipeline
is configured using configuration files, see this tutorial.
Message bus
In this example, the InOutput
and Step
instances communicate with each other through the MessageBus
, see this tutorial.
Foxglove Studio
The data generated in this example can be visualized using Foxglove Studio. See this page for instructions on how to install and set it up.
Download dataset#
Several free and open-source car driving datasets related to Autonomous Driving applications exist that can be used to get started with the MPMCA if you do not have your own data. Typically, these datasets contain measurements from an Inertial Measurement Unit (IMU), providing linear accelerations or specific forces and rotational rates (6 signals in total). Note that the MPMCA takes 9 signals as output reference: specific forces, rotational rates, and rotational accelerations. If you have a dataset without rotational accelerations, you can simply provide zeros for the reference rotational accelerations and specify an output error weight of 0 for those three channels.
In this example, we use the Audi Autonomous Driving Dataset (A2D2).1 The A2D2 dataset is very large, but you do not have to download it completely to follow this example. You can either use a simple script provided in the data folder or download the data yourself.
Download script#
Run the download_unpack_data.sh
bash script inside the data/a2d2
folder to automatically download and unpack the Gaimersheim data file to the correct location.
To run the script, move into the data/a2d2
folder and give the script execution rights, by issuing the following command:
chmod +x download_unpack_data.sh
Then, run the script through
./download_unpack_data.sh
You can use the config.json
file as provided in the applications/demo_oracle_predictor
directory.
Download data manually#
From the download page, download one of the "Bus signals" datasets (Gaimersheim, Ingolstadt, or Munich), or download the "Dataset Preview", which also contains a small "Bus signals" dataset.
This example assumes you to use the "Gaimersheim" file. Extract the file called bus_signals_20180810150607.json
from the camera_lidar/20180810_150607/
folder in the archive, and place it in the data/a2d2/
folder inside this repository. If you use a different file or place it on a different location, make sure you adjust the config.json
file inside applications/demo_oracle_predictor
.
Steps and InOutputs#
This section documents the Step and InOutputs involved in this example.
Required includes#
The main.cpp
of this example application needs to include the following files to be able to instantiate the InOutput
and Step
types that are not templated:
1#include "mpmca/pipeline/in_output/go_to_run.hpp"
2#include "mpmca/pipeline/step/json_playback.hpp"
The other InOutput
and Step
types are linked into the program in the other .cpp
files in the application folder.
These InOutput
and Step
types are discussed below.
ControlCommands#
The file control_commands.cpp
instantiates a ControlCommands<TSIM>
type for the MpmcaHexapod
simulator, and registers it with the InOutputRegister
(to make sure it can be instantiated through a configuration file).
1#include "mpmca/pipeline/in_output/control_commands.hpp"
2
3#include "mpmca/pipeline/in_output/control_commands.tpp"
4#include "mpmca_hexapod/mpmca_hexapod.hpp"
5
6using namespace mpmca::pipeline;
7
8template class in_output::ControlCommands<mpmca::control::MpmcaHexapod>;
9
10static InOutputRegistrar<
11 in_output::ControlCommands<mpmca::control::MpmcaHexapod>>
12 ControlCommandsRegistrar("ControlCommands");
The tasks of ControlCommands
are:
- to deal with computational overruns of the
PredictiveControl
step in theTask
, - to provide the correct initial state for each
Controller
update inMainTick()
, and - to provide the correct position-velocity-acceleration (PVA) set-points to be sent to the simulator (from another
InOutput
).
Computational overruns
Note that the generic functionality related to dealing with computational overruns is implemented inside the Pipeline
class. The ControlCommands
class implements the more specific behavior necessary to provide the correct control commands to the simulator when computational overruns occur.
FadeInertialReference#
The file fade_inertial_reference.cpp
instantiates a FadeInertialReference<TSIM>
type for the MpmcaHexapod
simulator, and registers it with the StepRegister
(to make sure it can be instantiated through a configuration file), in a similar way as was done for ControlCommands
.
The tasks of FadeInertialReference
are:
- to 'fade in' the output reference signals when entering the
RUN
state, - to 'fade out' the output reference signals when leaving the
RUN
state, and - to keep the global
StateMachine
inSTOPPING
until the simulator has reached zero velocity.
PredictiveControl#
The file predictive_control.cpp
instantiates a PredictiveControl<TSIM>
type for the MpmcaHexapod
simulator, and registers it with the StepRegister
, in a similar way as was done for ControlCommands
.
Include both the .hpp
and .tpp
files.
Note that the (templated) implementation of PredictiveControl
is placed outside the header file (.hpp
) in a separate file with .tpp
extension. Both need to be included.
The tasks of PredictiveControl
are:
- to create an
Controller
object of the correct type, - to pass all configuration options to the
Controller
, - to pass all relevant (input) messages from the
MessageBus
to theController
, - to call the
Prepare
andFeedback
functions of theController
in the right order and at the right moment, and - to put relevant data from the
Controller
onto (output) messages on theMessageBus
.
Note that the PredictiveControl
step is intended to perform the above listed tasks only, and you should not expect it to do anything else. All other functionality should be implemented in other Step
types that receive information from PredictiveControl
through messages on the MessageBus
. For example, the following tasks are to be handled by other Step
types:
- to check the validity of all input and output messages on the
MessageBus
(not part of the code base, to be implemented by the user), - to fade in or out the reference signals provided to
PredictiveControl
(seeFadeInertialReference
), - to gracefully start or stop the motion of the actual simulator (also see
FadeInertialReference
), or - to log information about the state of the
Controller
to a file on disk (seeMcapLogger
).
JsonPlayback#
The JsonPlayback
step does not depend on the type of simulator to be controlled, and thus does not require a separate .cpp
file in which a class template is instantiated.
The tasks of JsonPlayback
are:
- to load time-series data from disk containing a recording of inertial signals,
- to construct a valid output reference using the loaded data, based on the current time and the time steps on the prediction horizon.
McapLogger#
The file mcap_logger.cpp
instantiates an McapLogger<TSIM>
type for the MpmcaHexapod
simulator, and registers it with the StepRegister
, in a similar way as was done for ControlCommands
.
The task of McapLogger
is to take relevant data from the MessageBus
and save it to an MCAP file, for visualization by Foxglove Studio, see this page.
Run the demo#
To run the demo, execute the following command from the root of the repository:
./build/bin/demo_oracle_predictor -c applications/demo_oracle_predictor/config.json
This will run the Pipeline
in 'realtime' mode. That is, the program will try to run exactly as fast as the real world time (the time you see on a wall clock). For the "Dataset preview" data, this will take approximately 8 minutes. The realtime mode is the mode you need when controlling a simulator during a human-in-the-loop experiment. However, when calculating results for later inspection using Foxglove, you might want to let the program run as fast as possible for your hardware. To do so, add the --free
arguments:
./build/bin/demo_oracle_predictor -c applications/demo_oracle_predictor/config.json --free
The recorded MCAP data file will be called demo_oracle_predictor.mcap
and you can find it in the directory from which you run the application (in this case, the root of the repository).
Results#
The results can be inspected using Foxglove Studio. An example screenshot of typical cueing results is shown below. Click here to enlarge.
From the results, observe the following:
- The 'phase shift' between the reference output and expected output of the lateral and longitudinal motion cues is very small. That is, the shape of the expected output follows the shape of the reference output precisely, but with some scaling errors.
- Very few false cues can be observed in the lateral and longitudinal channels.
- The roll and pitch motion is used to provide lateral and longitudinal specific forces (typically referred to as "g-tilt"), but note that this effect was not 'programmed into' the algorithm manually. It just results automatically from the taken approach.
- Given the rather limited yaw motion space of a hexapod, the MPMCA will extensively 'pre-position' the simulator to obtain more space. Whether or not the person inside the simulator will be able to feel this pre-positioning depends on many factors. For this particular example, it is likely that it can be felt, as the pre-positioning rotational rate exceeds 5 deg/s.
- The MPMCA accurately replicates the 'low frequency' motions, such as cornering accelerations and braking/acceleration, but also replicates the 'high frequency' motions, such as road noise and bumps in the road.
Cueing improvements#
The cueing results obtained with this example will certainly not be the best results possible for this dataset and this simulator. Several improvements can be obtained from the following:
- Add the
ScaleInertialReference
Step to linearly scale the reference output signals. For theMpmcaHexapod
simulator, a good starting point is to scale the longitudinal and lateral specific forces by a factor of0.5
, and the yaw rotational rates by0.4
. - Modify the output error weights to emphasize certain degrees-of-freedom over others. In this example, the "magic-10" output error weights are used (i.e.,
1.0
for specific forces, and10.0
for rotational rates), but other values might lead to better results.
Bibliography#
-
Geyer, J., Kassahun, Y., Mahmudi, M., Ricou, X., Durgesh, R., Chung, A. S., Hauswald, L., Pham, V. H., Mühlegg, M., Dorn, S., Fernandez, T., Jänicke, M., Mirashi, S., Savani, C., Sturm, M., Vorobiov, O., Oelker, M., Garreis, S., & Schuberth, P. (2020). A2D2: Audi Autonomous Driving Dataset. https://www.a2d2.audi ↩