Hello World programming tutorial
This tutorial shows how to utilize esmini as a shared (dynamically loaded) library for use in a custom application. It can be used with or without esmini embedded viewer.
Preparations
The simplest preparation is to get the demo package from the latest relase and then head on to the steps below.
But, of course, if you already have checked out the esmini project from GitHub and compiled it you should already be set.
Just make sure that the shared library is available in the bin or lib folder, which should be available directly under esmini root. Exact filename depends on the platform as follows:
| Windows: |
esminiLib.dll |
| Linux: |
libesminiLib.so |
| Mac: |
libesminiLib.dylib |
How to build, run and debug "Hello World"
Windows/Visual Studio
First step: Create the solution file
Run from Hello-World_coding-example root folder:
mkdir build
cd build
cmake .. (will generate solution for multiple variants, including Release and Debug)
Build and run the application from command line
Build
cmake --build . --config Release (release variant), or
cmake --build . --config Debug (debug variant)
Run
-
open a command shell and put yourself in
Hello-World_coding-example/buildfolder -
add shared library location to the environment path variable, e.g:
CMD:set path=../../bin;%path%
PowerShell:$env:path+=";../../bin"
bash:PATH=$PATH:../../bin -
Launch application
CMD:
.\Debug\esmini-player.exeor
.\Release\esmini-player.exe(depending on variant)
PowerShell or bash:
./Debug/esmini-player.exeor
./Release/esmini-player.exe
Build, run and debug the application from Visual Studio
-
Open
esmini-player.slnin Visual Studio -
Build as usual (Ctrl-F7 or
Build→Build Solution) -
Set as startup project
-
Right click on esmini-player in Solution Explorer
-
Click on
Set as Startup Project
-
-
Tell the system where to find the shared library
-
Right click on esmini-player in Solution Explorer
-
Click on
Properties -
Select Configuration →
All Configurations -
In
Configuration Properties→Debugging→Environmentwrite:path=$(ProjectDir)/../../bin
or any other folder containing the esmini library
-
-
Run
-
Ctrl-F5to run without debug -
F5to debug
-
Linux
First step: Create the Makefile
Run from Hello-World_coding-example root folder:
mkdir build
cd build
then:
cmake .. -DCMAKE_BUILD_TYPE=Release for Release variant, or
cmake .. -DCMAKE_BUILD_TYPE=Debug for Debug variant
Build and run from command line
-
Build
cmake --build .or just
make -
Tell system where to look for esmini shared library (maybe not necessary)
export LD_LIBRARY_PATH=../../bin(on macOS: DYLD_LIBRARY_PATH) -
Launch application
./esmini-player
Build, run and debug from Visual Studio Code
Prerequisites: Install the following VS Code extensions:
-
C/C++
-
CMake Tools
Build
-
Open visual studio as Hello-World_coding-example as root folder
-
Open the Command Palette (Ctrl+Shift+P) and run
CMake: Select a Kit. Select the compiler you want to use. For example GCC 11.3.0 -
Open the Command Palette (Ctrl+Shift+P) run the
CMake: Select Variantcommand. Select Debug. -
Open the Command Palette (Ctrl+Shift+P) run the
CMake:Set Build Target. Select esmini-player. -
Open the Command Palette (Ctrl+Shift+P) and run the
CMake: Buildcommand, or select the build button from the Status bar.
Open main.cpp file in the Hello-World_coding-example folder and optionally introduce break points.
Run
-
Open the Command Palette (Ctrl+Shift+P) and run the
CMake: Run Without Debuggingcommand, or -
Use play button in the status bar, or
-
Shift-F5
Debug
-
Open the Command Palette (Ctrl+Shift+P) and run the
CMake: Debugcommand, or -
Use debug button in the status bar, or
-
Ctrl-F5
Next step
Now that you can build and run Hello World, it’s time to explore some functionality of esmini. Next section presents a few code examples to try out, e.g. by modifying main.cpp.
Examples
Hello world - load and play a scenario
#include "esminiLib.hpp"
int main(int argc, char* argv[])
{
SE_Init("../../resources/xosc/cut-in.xosc", 0, 1, 0, 0);
for (int i = 0; i < 500; i++)
{
SE_Step();
}
SE_Close();
return 0;
}
Exercise: Change scenario to pedestrian.xosc, then compile and run the program again.
Add optional argument to load any scenario
#include "esminiLib.hpp"
int main(int argc, char* argv[])
{
if (argc > 1)
{
SE_InitWithArgs(argc, const_cast<const char**>(argv));
}
else
{
SE_Init("../resources/xosc/cut-in.xosc", 0, 1, 0, 0);
}
for (int i = 0; i < 500; i++)
{
SE_Step();
}
SE_Close();
return 0;
}
You can now specify esmini arguments according to esmini launch commands.
Example:
./esmini-player --window 60 60 1000 500 --osc ../resources/xosc/pedestrian.xosc --trails
Fetch state of scenario objects
This example shows how to retrieve the state of scenario objects.
We also check the return code from the initialization and react on any error.
#include "stdio.h"
#include "esminiLib.hpp"
int main(int argc, char* argv[])
{
(void)argc;
(void)argv;
if (SE_Init("../resources/xosc/cut-in.xosc", 0, 1, 0, 0) != 0)
{
printf("Failed to initialize scenario\n");
return -1;
}
for (int i = 0; i < 500; i++)
{
SE_Step();
for (int j = 0; j < SE_GetNumberOfObjects(); j++)
{
SE_ScenarioObjectState state;
SE_GetObjectState(SE_GetId(j), &state);
printf("time [%.2f] object[%d] id %d pos[%.2f, %.2f] %.2f %.2f odometer: %.2f\n",
state.timestamp,
j,
SE_GetId(j),
state.x,
state.y,
state.wheel_angle,
state.wheel_rot,
SE_GetObjectOdometer(SE_GetId(j)));
}
}
SE_Close();
return 0;
}
External control of Ego
A silly example showing how you can just take control over vehicle state via the API. The Ego car will move one meter along the Y-axis for each frame while rotating…
Now we will also introduce the quit_flag, which lets you quit by pressing 'Esc' key.
In addition we’ll try out the alignment feature. By default objects will be aligned to road surface. This behavior can be controlled with alignment settings. In below example, the Ego vehicle will be aligned to road surface except during iterations 100-200 where it will obey the reported Z coordinate and move accordingly to elevation/Z = 10 meter.
#include "esminiLib.hpp"
#include <stdio.h>
int main(int argc, char* argv[])
{
const char* filename = argc > 1 ? argv[1] : "../resources/xosc/cut-in_external.xosc";
SE_ScenarioObjectState state;
double z = 0.0;
if (SE_Init(filename, 0, 1, 0, 0) != 0)
{
return -1;
}
for (int i = 0; i < 500 && SE_GetQuitFlag() != 1; i++)
{
SE_ReportObjectPos(SE_GetId(0), 8.0, i, z, 1.57 + 0.01 * i, 0.0, 0.0);
SE_Step();
// fetch position in terms of road coordinates
SE_GetObjectState(SE_GetId(0), &state);
printf("road_id: %d s: %.3f lane_id %d lane_offset: %.3f z: %.2f\n", state.roadId, state.s, state.laneId, state.laneOffset, state.z);
if (i == 100)
{
z = 10.0;
printf("Release relative road alignment, set absolute z = %.2f\n", z);
SE_SetObjectPositionMode(SE_GetId(0),
SE_PositionModeType::SE_SET,
SE_PositionMode::SE_Z_ABS); // release relative alignment to road surface
}
if (i == 200)
{
z = 0.0;
printf("Restore relative road alignment, set relative z = %.2f\n", z);
SE_SetObjectPositionMode(SE_GetId(0),
SE_PositionModeType::SE_SET,
SE_PositionMode::SE_Z_REL); // enforce relative alignment to road surface
}
}
SE_Close();
return 0;
}
Exercise: Change heading with i, e.g:
SE_ReportObjectPos(0, 0.0f, 8.0f, (float)i, 0.0f, 1.57f + 0.01f*i, 0.0f, 0.0f);
Yes, it looks crazy! But it demonstrates how an application totally can take control of a vehicle.
Control controllers
Try to run cut-in_interactive.xosc, as below.
#include "esminiLib.hpp"
int main(int argc, char* argv[])
{
(void)argc;
(void)argv;
SE_Init("../resources/xosc/cut-in_interactive.xosc", 0, 1, 0, 0);
for (int i = 0; i < 2000 && SE_GetQuitFlag() != 1; i++)
{
SE_Step();
}
SE_Close();
return 0;
}
Control the Ego vehicle with arrow keys.
To disable controllers and hand over to default scenario behavior set first argument flag (see headerfile esminiLib.hpp):
#include "esminiLib.hpp"
int main(int, char**)
{
SE_Init("../resources/xosc/cut-in_interactive.xosc", 1, 1, 0, 0);
for (int i = 0; i < 2000 && SE_GetQuitFlag() != 1; i++)
{
SE_Step();
}
SE_Close();
return 0;
}
Ideal sensors
#include "stdio.h"
#include "esminiLib.hpp"
#define MAX_HITS 10
int main(int, char**)
{
SE_Init("../resources/xosc/cut-in.xosc", 0, 1, 0, 0);
SE_AddObjectSensor(0, 2.0, 1.0, 0.5, 1.57, 1.0, 50.0, 1.57, MAX_HITS);
SE_AddObjectSensor(0, -1.0, 0.0, 0.5, 3.14, 0.5, 20.0, 1.57, MAX_HITS);
// Turn on visualization of object sensors, toggle key 'r'
SE_ViewerShowFeature(1, true);
for (int i = 0; i < 2000 && !(SE_GetQuitFlag() == 1); i++)
{
SE_Step();
int objList[MAX_HITS];
for (int j = 0; j < 2; j++) // iterate over added sensors
{
int nHits = SE_FetchSensorObjectList(j, objList);
for (int k = 0; k < nHits; k++)
{
printf("Sensor[%d] detected obj: %d\n", j, objList[k]);
// Get some info of that detected object
SE_ScenarioObjectState state;
SE_GetObjectState(objList[k], &state);
printf("object[%d] pos: (%.2f, %.2f) heading: %.2f\n", objList[k], state.x, state.y, state.h);
}
}
}
SE_Close();
return 0;
}
Note: If you want M_PI, add on top (before includes): #define _USE_MATH_DEFINES
Collision detection
There are two approaches to collision detection that fit different use cases:
1. By scenario
Making use of the OpenSCENARIO CollisionCondition a collision can be detected and act upon. This can be useful for example if a scenario or test case should end in case of Ego vehicle gets involved in a collision.
See example EnvironmentSimulator/Unittest/xosc/test-collision-detection.xosc. To run it from command line:
./bin/esmini --window 60 60 800 400 --osc ./EnvironmentSimulator/Unittest/xosc/test-collision-detection.xosc
Control the Ego car with keyboard arrow keys. Press "up" to accelerate, and "left" or "right" to steer. See output in console when colliding with the two other cars.
The interactive controller can be disabled. Then the Ego car will get the speed from the scenario. Run:
./bin/esmini --window 60 60 800 400 --osc ./EnvironmentSimulator/Unittest/xosc/test-collision-detection.xosc --disable_controllers
Note: In this example the action is empty, i.e. the event is triggered on collision but nothing really happens, other than logging the trigger result. In a real use case there could be an actual action, e.g. immediate stop by setting speed to zero in a single step. Another usage is to use the condition in a scenario stop trigger, e.g. to quit the test case as soon as collision happens.
2. By API
In addition, or as alternative, to detect collisions via OpenSCENARIO condition esmini can check for collisions between any objects regardless of the scenario. This is a feature that must be enabled (SE_CollisionDetection(true)) since it’s off by default to avoid unnecessary performance penalties.
See code example:
#include "esminiLib.hpp"
#include "stdio.h"
int main(void)
{
SE_Init("../EnvironmentSimulator/Unittest/xosc/test-collision-detection.xosc", 1, 1, 0, 0);
SE_CollisionDetection(true);
for (int i = 0; i < 500; i++)
{
SE_Step();
for (int j = 0; j < SE_GetNumberOfObjects(); j++)
{
for (int k = 0; k < SE_GetObjectNumberOfCollisions(j); k++)
{
printf("Collision[%d]: %d\n", j, SE_GetObjectCollision(j, k));
}
}
}
return 0;
}
Note: It uses the same scenario file as the above (1. By scenario) but the complete "CollisionManeuver" could be removed since no CollisionCondition is needed for API based collision detection. Actually, if maneuver is present the console will show log info from both the condition and the API driven collision detections.
Simple speed control
As an alternative to the external control examples above, you can control the speed of an object directly. Just note that any triggered scenario actions involving the object might conflict with speed settings via lib API. Recommendation is control an object either via API or scenario file. That said, the combination can be useful for some use cases.
The code will modulate speed of Ego (first vehicle) between 2 and 20 mps.
#include "esminiLib.hpp"
#include <iostream>
int main(int argc, char **argv)
{
double acc = 10; // initial acceleration
double speed = 2.0; // initial speed
if (argc > 1)
{
SE_Init(argv[1], 0, 1, 0, 0);
}
else
{
printf("Usage: %s <path to xosc file>\n", argv[0]);
return -1;
}
while (SE_GetQuitFlag() != 1)
{
speed += acc * SE_GetSimTimeStep(); // get latest time step from simulation
// modulate speed by changing sign of acceleration now and then
if (speed < 2.0)
{
acc = 10;
}
else if (speed > 20.0)
{
acc = -10;
}
// report updated speed
SE_ReportObjectSpeed(0, speed);
// step the simulation in natural speed, change to SE_Step(<time-step>) for fixed timestep
SE_Step();
}
SE_Close();
return 0;
}
Example run command, from esmini/code-examples-bin folder:
./speed_controller ../resources/xosc/cut-in.xosc
There is also a Python version of this example:
EnvironmentSimulator/code-examples/hello_world/speed_controller.py
Inject actions
This example demonstrates how you can control longitudinal and lateral motion by applying the following actions:
-
SpeedAction
-
LaneChangeAction
-
LaneOffsetAction
Currently (v2.37.0) the action injection feature is limited to these three actions, but it’s rather easy to extend if needed.
The code will apply three actions according as follows:
-
after 2 seconds, make a slight movement (lane offset) of 0.45m to the right
-
after 7 seconds, make a lane change to the left
-
after 8 seconds, consider to do another lane change, but skip since another is already ongoing
-
after 9.5 seconds, brake softly (braking will start before lane change is done)
-
after 11.0 seconds, brake harder to a stop (will cancel the ongoing soft brake action)
#include "esminiLib.hpp"
#include <string.h>
#include <iostream>
#define SMALL_NUMBER 1e-6
int main(int argc, char **argv)
{
double dt = -1.0; // default to variable timestep
if (argc > 2)
{
if (SE_InitWithArgs(argc, const_cast<const char **>(argv)) != 0)
{
printf("Error: Could not initialize scenario %s\n", argv[1]);
return -1;
}
for (int i = 2; i < argc; i++)
{
if (i < argc - 1 && strcmp(argv[i], "--fixed_timestep") == 0)
{
dt = atof(argv[i + 1]); // use any provided fixed timestep
}
}
}
else if (argc > 1)
{
if (SE_Init(argv[1], 0, 1, 0, 0) != 0)
{
printf("Error: Could not initialize scenario %s\n", argv[1]);
return -1;
}
}
else
{
printf("Usage: %s <path to xosc file>\n", argv[0]);
return -1;
}
int state = 0;
while (SE_GetQuitFlag() == 0 && SE_GetSimulationTime() < 17.0)
{
if (state == 0 && SE_GetSimulationTime() > 2.0 + SMALL_NUMBER)
{
printf("Injecting lane offset action\n");
SE_LaneOffsetActionStruct lane_offset;
lane_offset.id = 0; // id of object to perform action
lane_offset.offset = -0.45; // target offset in m
lane_offset.maxLateralAcc = 0.5; // max lateral acceleration in m/s^2
lane_offset.transition_shape = 0; // cubic
SE_InjectLaneOffsetAction(&lane_offset);
state++;
}
else if (state == 1 && SE_GetSimulationTime() > 7.0 + SMALL_NUMBER)
{
printf("Injecting lane change action\n");
SE_LaneChangeActionStruct lane_change;
lane_change.id = 0; // id of object to perform action
lane_change.mode = 1; // relative (own vehicle)
lane_change.target = 1; // target lane id (relative)
lane_change.transition_shape = 2; // sinusoidal
lane_change.transition_dim = 2; // time
lane_change.transition_value = 3.0; // s
SE_InjectLaneChangeAction(&lane_change);
state++;
}
else if (state == 2 && SE_GetSimulationTime() > 8.0 + SMALL_NUMBER)
{
if (SE_InjectedActionOngoing(5)) // 5 = LAT_LANE_CHANGE
{
printf("Lane change already ongoing, skipping second lane change\n");
}
else
{
printf("Injecting lane change action 2\n");
SE_LaneChangeActionStruct lane_change;
lane_change.id = 0; // id of object to perform action
lane_change.mode = 1; // relative (own vehicle)
lane_change.target = -1; // target lane id (relative)
lane_change.transition_shape = 2; // sinusoidal
lane_change.transition_dim = 2; // time
lane_change.transition_value = 3.0; // s
SE_InjectLaneChangeAction(&lane_change);
}
state++;
}
else if (state == 3 && SE_GetSimulationTime() > 9.5 + SMALL_NUMBER) // slightly overlapping lane change action
{
printf("Injecting speed action - soft brake\n");
SE_SpeedActionStruct speed;
speed.id = 0; // id of object to perform action
speed.speed = 0.0; // target speed in m/s
speed.transition_shape = 0; // cubic
speed.transition_dim = 1; // rate
speed.transition_value = 3.0; // m/s^2
SE_InjectSpeedAction(&speed);
state++;
}
else if (state == 4 && SE_GetSimulationTime() > 11.0 + SMALL_NUMBER) // slightly overlapping lane change action
{
printf("Injecting speed action - hard brake\n");
SE_SpeedActionStruct speed;
speed.id = 0; // id of object to perform action
speed.speed = 0.0; // target speed in m/s
speed.transition_shape = 1; // cubic
speed.transition_dim = 1; // rate
speed.transition_value = 8.0; // m/s^2
SE_InjectSpeedAction(&speed);
state++;
}
if (dt < 0.0)
{
SE_Step();
}
else
{
SE_StepDT(dt);
}
}
SE_Close();
return 0;
}
Example run command, from esmini/code-examples-bin folder:
./action_injection ../resources/xosc/cut-in.xosc
There is also a Python version of this example:
EnvironmentSimulator/code-examples/hello_world/action_injection.py
Driver model
Using a simple vehicle model this example demonstrates how a driver model can interact with the scenario in terms of pedal and steering input. This time we use the ExternalController again to ensure any scenario actions is not conflicting with the driver model.
To show different variants we also show how to set scenario parameters during intialization, via callbacks. In effect this is a way to achieve runtime variants of the same basic scenario.
Before heading into the application code we will look into the scenario file EnvironmentSimulator/code-examples/test-driver/test-driver.xosc.
Now, let’s have a look inside it to see how to activate the ExternalController, which will prevent the DefaultController to interfere with the Ego vehicle and instead hand over exclusive control to our application. You can skip this and go to the C++ code example below if you’re not interested in the controller setup.
-
Open test-driver.xosc
-
Look in the Entities section, under the
<ScenarioObject name="Ego"\>element. Here the controller is defined and assigned to the Ego vehicle.
<ObjectController>
<Controller name="MyExternalControllerWithGhost">
<Properties>
<Property name="esminiController" value="ExternalController" />
<Property name="useGhost" value="$GhostMode" />
<Property name="headstartTime" value="2" />
</Properties>
</Controller>
</ObjectController>
Note: The GhostMode parameter is set to true or false in the ParameterDeclarations section in the top of the scenario file.
-
Then the initial position is set. This could instead be done by the application, but it’s convenient to specify it in the scenario file.
<PrivateAction>
<TeleportAction>
<Position>
<LanePosition roadId="1" laneId="-1" offset="0" s="50"/>
</Position>
</TeleportAction>
</PrivateAction>
-
Finally we need to activate the controller on both lateral and longitudinal domains.
<PrivateAction>
<ActivateControllerAction longitudinal="true" lateral="true" />
</PrivateAction>
The reason for putting it AFTER the positioning is that oterwise the position action would have no effect, since once the controller is activated all scenario actions will be ignored. The controller then having exclusive control.
Now let’s head into the code example. It will run the scenario three times:
-
External controller without ghost mode
-
just look ahead and follow along current lane. Find point along the lane and steer towards it.
-
-
External controller with ghost mode and time based lookahead
-
find the state of ghost at given time offset. Use it for steering and speed target.
-
-
External controller with ghost mode and position based lookahead
-
given the current Ego position, find ghost state at some look ahead distance along its trail. Use it for steering and speed target.
-
Now, study the code and perhaps play around mainpulating some values.
#include "stdio.h"
#include "math.h"
#include <string>
#include "esminiLib.hpp"
void paramDeclCB(void* user_arg)
{
bool ghostMode = *(static_cast<bool*>(user_arg));
SE_LogMessage((std::string("Running with ghostMode = ").append(ghostMode == true ? "true" : "false")).c_str());
SE_SetParameterBool("GhostMode", ghostMode);
}
int main(int argc, char* argv[])
{
(void)argc;
(void)argv;
const double defaultTargetSpeed = 50.0;
const double curveWeight = 30.0;
const double throttleWeight = 0.1;
const double duration = 35.0;
bool ghostMode[3] = {false, true, true};
SE_SimpleVehicleState vehicleState = {0, 0, 0, 0, 0, 0, 0, 0};
SE_ScenarioObjectState objectState;
SE_RoadInfo roadInfo;
for (int i = 0; i < 3; i++)
{
SE_RegisterParameterDeclarationCallback(paramDeclCB, &ghostMode[i]);
if (SE_Init("../EnvironmentSimulator/code-examples/test-driver/test-driver.xosc", 0, 1, 0, 0) != 0)
{
SE_LogMessage("Failed to initialize the scenario, quit\n");
return -1;
}
// Lock object to the original lane
// If setting to false, the object road position will snap to closest lane
SE_SetLockOnLane(0, true);
// Initialize the vehicle model, fetch initial state from the scenario
SE_GetObjectState(0, &objectState);
void* vehicleHandle = SE_SimpleVehicleCreate(objectState.x, objectState.y, objectState.h, 4.0, 0.0);
SE_SimpleVehicleSteeringRate(vehicleHandle, 6.0);
// show some road features, including road sensor
SE_ViewerShowFeature(4 + 8, true); // NODE_MASK_TRAIL_DOTS (1 << 2) & NODE_MASK_ODR_FEATURES (1 << 3),
// Run for specified duration or until 'Esc' button is pressed
while (SE_GetSimulationTime() < duration && SE_GetQuitFlag() != 1)
{
// Get simulation delta time since last call (first will be minimum timestep)
double dt = SE_GetSimTimeStep();
// Get road information at a point some speed dependent distance ahead
double targetSpeed;
if (ghostMode[i] == true)
{
// ghost version
double ghost_speed = 0.0;
double timestamp = 0.0;
if (i % 2 == 0) // alternate between time based and position based look ahead modes
{
// Time based look ahead
SE_GetRoadInfoGhostTrailTime(0, SE_GetSimulationTime() + 0.25, &roadInfo, &ghost_speed);
}
else
{
// Position based Time based look ahead
SE_GetRoadInfoAlongGhostTrail(0, 5 + 0.75 * vehicleState.speed, &roadInfo, &ghost_speed, ×tamp);
}
targetSpeed = ghost_speed;
}
else
{
// Look ahead along the road, to establish target info for the driver model
SE_GetRoadInfoAtDistance(0, 5 + 0.75 * vehicleState.speed, &roadInfo, 0, true);
// Slow down when curve ahead - CURVE_WEIGHT is the tuning parameter
targetSpeed = defaultTargetSpeed / (1 + curveWeight * fabs(roadInfo.angle));
}
// Accelerate or decelerate towards target speed - THROTTLE_WEIGHT tunes magnitude
double throttle = throttleWeight * (targetSpeed - vehicleState.speed);
// Step vehicle model with driver input, but wait until time > 0
if (SE_GetSimulationTime() > 0 && !SE_GetPauseFlag())
{
// Steer towards where the point
double steerAngle = roadInfo.angle;
SE_SimpleVehicleControlAnalog(vehicleHandle, dt, throttle, steerAngle);
}
// Fetch updated state and report to scenario engine
SE_SimpleVehicleGetState(vehicleHandle, &vehicleState);
// Report updated vehicle position and heading. z, pitch and roll will be aligned to the road
SE_ReportObjectPosXYH(0, vehicleState.x, vehicleState.y, vehicleState.h);
// The following values are not necessary to report.
// If not reported, esmini will calculate based on motion over time
// but for accuracy it's recommendeded to report if available.
// wheel status (revolution and steering angles)
SE_ReportObjectWheelStatus(0, vehicleState.wheel_rotation, vehicleState.wheel_angle);
// speed (along vehicle longitudinal (x) axis)
SE_ReportObjectSpeed(0, vehicleState.speed);
// Finally, update scenario using same time step as for vehicle model
SE_StepDT(dt);
}
SE_Close();
}
return 0;
}
Don’t worry about the stationary red car on the road, you’ll just drive through it.
Try experimenting with the driver settings, e.g. increase lookahead distance factor from 0.75 to 1.75.
When running the application, press key 'j' to toggle ghost trail dots and lines visualization.
Challenge: Attach a front looking sensor to detect it and have the driver to brake to avoid collision…
Ghost concept in brief
In the first loop the driver model is just capable of driving along the specified lane. It’s totally detached from any scenario events.
The ghost concept is a solution for a driver model to perform scenario actions. Basically it will launch a fore-runner to perform the scenario actions. The trajectory, including speed, is registered into a "trail" which can then be used as reference for steering and speed target.
Ghost mode is a parameter of the external controller. Normally this is set in the scenario, for example in test-driver.xosc, change line:
<ParameterDeclaration name="GhostMode" parameterType="boolean" value="false"/>
to:
<ParameterDeclaration name="GhostMode" parameterType="boolean" value="true"/>
However, in the example code this parameter is controlled by the paramDeclCB() callback. Once it’s registered with SE_RegisterParameterDeclarationCallback() it will be called each time esmini is initialized (SE_Init()).
OSI groundtruth
To access OSI data we first need to complement the build script (CMakeLists.txt) with OSI include and library info. For example:
Windows:
include_directories(. ../include ../EnvironmentSimulator/Libraries/esminiLib ../externals/osi/v10/include)
link_directories(. ../bin ../externals/osi/v10/lib)
target_link_libraries(${TARGET} esminiLib libprotobuf open_simulation_interface_pic)
Linux:
include_directories(. ../include ../EnvironmentSimulator/Libraries/esminiLib ../externals/osi/linux/include)
link_directories(. ../bin ../externals/osi/linux/lib)
target_link_libraries(${TARGET} esminiLib protobuf open_simulation_interface_pic)
Note:
-
Replace foldername "v10" with linux or mac depending on your platform.
-
If linking with custom applications or libraries: OSI and Google Protobuf versions needs to be consistent (at least major version nr), also with the versions used in esmini (see here).
Then run cmake .. from the build folder to apply the changes in CMakeFiles.cxx.
The following code will update, fetch and print some OSI data each frame.
#include "esminiLib.hpp"
#include "osi_common.pb.h"
#include "osi_object.pb.h"
#include "osi_groundtruth.pb.h"
#include "osi_version.pb.h"
int main(int argc, char* argv[])
{
(void)argc;
(void)argv;
const osi3::GroundTruth* gt;
SE_EnableOSIFile(0); // 0 or "" will result in default filename, ground_truth.osi
SE_SetOSIStaticReportMode(SE_OSIStaticReportMode::DEFAULT);
SE_Init("../resources/xosc/cut-in_simple.xosc", 0, 1, 0, 0);
// Fetch initial OSI struct, this will also update the OSI data
gt = reinterpret_cast<const osi3::GroundTruth*>(SE_GetOSIGroundTruthRaw());
// Lane boundaries (static road info only available in first OSI frame)
printf("lane boundaries: %d\n", gt->lane_boundary_size());
for (int j = 0; j < gt->lane_boundary_size(); j++)
{
printf(" lane boundary %d, nr of boundary points: %d\n", j, gt->lane_boundary(j).boundary_line_size());
#if 0 // change to 1 in order to print all boundary points
for (int k = 0; k < gt->lane_boundary(j).boundary_line_size(); k++)
{
printf(" (%.2f, %.2f)\n",
gt->lane_boundary(j).boundary_line(k).position().x(),
gt->lane_boundary(j).boundary_line(k).position().y());
}
#endif
}
for (int i = 0; i < 4; i++)
{
SE_StepDT(0.01); // ground truth will be automatically updated each step if we have either an OSIFile or fetched a pointer to the
// osi3::GroundTruth struct
// Print timestamp
printf("Frame %d timestamp: %.2f\n",
i + 1,
static_cast<double>(gt->timestamp().seconds()) + 1E-9 * static_cast<double>(gt->timestamp().nanos()));
// Static content such as lane boundaries should be 0 at this point (we have SE_OSIStaticReportMode::DEFAULT, change to API or API_AND_LOG to
// get static data)
printf("lane boundaries: %d\n", gt->lane_boundary_size());
// Road markings, e.g. zebra lines
printf("road markings: %d\n", gt->road_marking_size());
// Moving objects
printf("moving objects: %d\n", gt->moving_object_size());
#if 1 // change to 1 in order to print some moving object state info
// Print object id, position, orientation and velocity
for (int j = 0; j < gt->moving_object().size(); j++)
{
printf(" obj id %u pos (%.2f, %.2f, %.2f) orientation (%.2f, %.2f, %.2f) vel (%.2f, %.2f, %.2f) acc (%.2f, %.2f, %.2f)\n",
static_cast<unsigned int>(gt->moving_object(j).id().value()),
gt->moving_object(j).base().position().x(),
gt->moving_object(j).base().position().y(),
gt->moving_object(j).base().position().z(),
gt->moving_object(j).base().orientation().yaw(),
gt->moving_object(j).base().orientation().pitch(),
gt->moving_object(j).base().orientation().roll(),
gt->moving_object(j).base().velocity().x(),
gt->moving_object(j).base().velocity().y(),
gt->moving_object(j).base().velocity().z(),
gt->moving_object(j).base().acceleration().x(),
gt->moving_object(j).base().acceleration().y(),
gt->moving_object(j).base().acceleration().z());
}
#endif
// Moving objects
printf("stationary objects: %d\n", gt->stationary_object_size());
}
SE_Close();
return 0;
}
Python binding
A Python wrapper for esmini can easily be created using "ctypes" (thanks David Kaplan for the tip!). This section presents a few examples to get you started.
Minimalistic esmini Python player
The script below works on Windows.
import ctypes
se = ctypes.CDLL("../bin/esminiLib.dll")
se.SE_Init(b"../resources/xosc/cut-in.xosc", 1, 1, 0, 0, 2)
for i in range (500):
se.SE_Step()
-
Create the file
esmini-win-player.pyinesmini/Hello-World_coding-examplefolder, copy the code into it. -
Make sure the esminiLib is present in
esmini/binfolder. -
Run the script from its folder as:
python esmini-win-player.py
Note: Library name varies with the platform as mentioned above (see Preparations)
Below is a bit more flexible variant:
-
Portable: Works on all supported platforms
-
Provide scenario via argument
-
Quit at press Escape or end of scenario
import ctypes
import sys
if sys.platform == "linux" or sys.platform == "linux2":
se = ctypes.CDLL("../bin/libesminiLib.so")
elif sys.platform == "darwin":
se = ctypes.CDLL("../bin/libesminiLib.dylib")
elif sys.platform == "win32":
se = ctypes.CDLL("../bin/esminiLib.dll")
else:
print("Unsupported platform: {}".format(sys.platform))
quit()
if (len(sys.argv) < 2):
print('Usage: {} <xosc file>'.format(sys.argv[0]))
exit(-1)
se.SE_Init(sys.argv[1].encode('ascii'), 0, 1, 0, 0)
while not se.SE_GetQuitFlag():
se.SE_Step()
That was a minimalistic introduction. Following examples are located under the EnvironmentSimulator/code-examples folder. To run them, again make sure the esminiLib is present in esmini/bin folder. Run each script from its folder.
Initialize esmini by flexible argument list
Instead of using the limited SE_Init() function you can pass any arguments using SE_InitWithArgs()
'''
demonstrate how to initialize esmini with arguments instead of a few limited arguments
using ideas from: https://comp.lang.python.narkive.com/RUdYlz64/trying-to-pass-sys-argv-as-int-argc-char-argv-using-ctypes
Instruction:
- make sure the esmini shared library (esminiLib.dll or esminiLib.so) is present in esmini/bin folder
- if not, either compile esmini (see User guide) or fetch bin package release
- from this folder (where this code module is), run: python ./init_by_args.py
'''
import ctypes as ct
import sys
if sys.platform == "linux" or sys.platform == "linux2":
se = ct.CDLL("../../../bin/libesminiLib.so")
elif sys.platform == "darwin":
se = ct.CDLL("../../../bin/libesminiLib.dylib")
elif sys.platform == "win32":
se = ct.CDLL("../../../bin/esminiLib.dll")
else:
print("Unsupported platform: {}".format(platform))
quit()
# specify arguments types of esmini function
se.SE_InitWithArgs.argtypes = [ct.c_int, ct.POINTER(ct.POINTER(ct.c_char))]
# create the list of arguments
args = [
"--window", "60", "60", "800", "400",
"--osc", "../resources/xosc/cut-in.xosc",
]
# prepare argument list for ctypes use
argv = (ct.POINTER(ct.c_char) * len(args))()
argc = len(argv)
for i, arg in enumerate(args):
argv[i] = ct.create_string_buffer(arg.encode())
# init esmini
if se.SE_InitWithArgs(argc, argv) != 0:
exit(-1)
# execute esmini until end of scenario or user requested quit by ESC key
while se.SE_GetQuitFlag() == 0:
se.SE_Step()
Forward command line arguments
How to just forward any argument provided from command line:
'''
demonstrate how to forward command line arguments to esmini
using ideas from: https://comp.lang.python.narkive.com/RUdYlz64/trying-to-pass-sys-argv-as-int-argc-char-argv-using-ctypes
Instruction:
- make sure the esmini shared library (esminiLib.dll or esminiLib.so) is present in esmini/bin folder
- if not, either compile esmini (see User guide) or fetch bin package release
- from this folder (where this code module is), run: python ./forward_cmd_args.py <esmini command line arguments>
- Example: python ./forward_cmd_args.py ../../../resources/xosc/cut-in.xosc --road_features on --bounding_boxes
'''
import ctypes as ct
import sys
if sys.platform == "linux" or sys.platform == "linux2":
se = ct.CDLL("../../../bin/libesminiLib.so")
elif sys.platform == "darwin":
se = ct.CDLL("../../../bin/libesminiLib.dylib")
elif sys.platform == "win32":
se = ct.CDLL("../../../bin/esminiLib.dll")
else:
print("Unsupported platform: {}".format(platform))
quit()
# specify arguments types of esmini function
se.SE_InitWithArgs.argtypes = [ct.c_int, ct.POINTER(ct.POINTER(ct.c_char))]
# fetch command line arguments
argc = len(sys.argv)
argv = (ct.POINTER(ct.c_char) * (argc + 1))()
for i, arg in enumerate(sys.argv):
argv[i] = ct.create_string_buffer(arg.encode('utf-8'))
# init esmini
if se.SE_InitWithArgs(argc, argv) != 0:
exit(-1)
# execute esmini until end of scenario or user requested quit by ESC key
while se.SE_GetQuitFlag() == 0:
se.SE_Step()
Get object states
How to retrieve the state of all scenario objects:
'''
demonstrate how to get scenario object states
Instruction:
- make sure the esmini shared library (esminiLib.dll or esminiLib.so) is present in esmini/bin folder
- if not, either compile esmini (see User guide) or fetch bin package release
- from this folder (where this code module is), run: python ./get_states.py
'''
import ctypes
from sys import platform
if platform == "linux" or platform == "linux2":
se = ctypes.CDLL("../../../bin/libesminiLib.so")
elif platform == "darwin":
se = ctypes.CDLL("../../../bin/libesminiLib.dylib")
elif platform == "win32":
se = ctypes.CDLL("../../../bin/esminiLib.dll")
else:
print("Unsupported platform: {}".format(platform))
quit()
# Definition of SE_ScenarioObjectState struct
class SEScenarioObjectState(ctypes.Structure):
_fields_ = [
("id", ctypes.c_int),
("model_id", ctypes.c_int),
("control", ctypes.c_int),
("timestamp", ctypes.c_double),
("x", ctypes.c_double),
("y", ctypes.c_double),
("z", ctypes.c_double),
("h", ctypes.c_double),
("p", ctypes.c_double),
("r", ctypes.c_double),
("roadId", ctypes.c_int),
("junctionId", ctypes.c_int),
("t", ctypes.c_double),
("laneId", ctypes.c_int),
("laneOffset", ctypes.c_double),
("s", ctypes.c_double),
("speed", ctypes.c_double),
("centerOffsetX", ctypes.c_double),
("centerOffsetY", ctypes.c_double),
("centerOffsetZ", ctypes.c_double),
("width", ctypes.c_double),
("length", ctypes.c_double),
("height", ctypes.c_double),
("objectType", ctypes.c_int),
("objectCategory", ctypes.c_int),
("wheelAngle", ctypes.c_double),
("wheelRot", ctypes.c_double),
("visibilityMask", ctypes.c_int)
]
se.SE_Init(b"../resources/xosc/cut-in.xosc", 0, 1, 0, 0)
obj_state = SEScenarioObjectState() # object that will be passed and filled in with object state info
for i in range(500):
for j in range(se.SE_GetNumberOfObjects()):
se.SE_GetObjectState(se.SE_GetId(j), ctypes.byref(obj_state))
print('Frame {} Time {:.2f} ObjId {} roadId {} laneId {} laneOffset {:.2f} s {:.2f} x {:.2f} y {:.2f} heading {:.2f} speed {:.2f} wheelAngle {:.2f} wheelRot {:.2f}'.format(
i, obj_state.timestamp, obj_state.id, obj_state.roadId, obj_state.laneId, obj_state.laneOffset,
obj_state.s, obj_state.x, obj_state.y, obj_state.h, obj_state.speed * 3.6, obj_state.wheelAngle, obj_state.wheelRot))
se.SE_Step()
Example use of esminiRMLib (RoadManager)
-
Make sure the esminiRMLib is present in
esmini/binfolder -
In the code, check filepath to the OpenDRIVE file to load (current search path should work when script is copied to and run from the esmini/Hello-World_coding-example folder)
'''
demonstrate how to use esmini esminiRMLib (road manager lib) in a Python context
Instruction:
- make sure the esmini shared library (esminiLib.dll or esminiLib.so) is present in esmini/bin folder
- if not, either compile esmini (see User guide) or fetch bin package release
- from this folder (where this code module is), run: python ./use_roadmanager.py
'''
import ctypes as ct
import sys
if sys.platform == "linux" or sys.platform == "linux2":
rm = ct.CDLL("../../../bin/libesminiRMLib.so")
elif sys.platform == "darwin":
rm = ct.CDLL("../../../bin/libesminiRMLib.dylib")
elif sys.platform == "win32":
rm = ct.CDLL("../../../bin/esminiRMLib.dll")
else:
print("Unsupported platform: {}".format(sys.platform))
sys.exit(-1)
# Definition of RM_PositionData struct - should match esminiRMLib::RM_PositionData struct
class RM_PositionData(ct.Structure):
_fields_ = [
("x", ct.c_double),
("y", ct.c_double),
("z", ct.c_double),
("h", ct.c_double),
("p", ct.c_double),
("r", ct.c_double),
("h_relative", ct.c_double),
("road_id", ct.c_int),
("junction_id", ct.c_int), # -1 if not in a junction
("lane_id", ct.c_int),
("lane_offset", ct.c_double),
("s", ct.c_double),
]
# Specify argument types to a few functions
rm.RM_SetWorldPosition.argtypes = [ct.c_int, ct.c_double, ct.c_double, ct.c_double, ct.c_double, ct.c_double, ct.c_double]
rm.RM_SetLanePosition.argtypes = [ct.c_int, ct.c_int, ct.c_int, ct.c_double, ct.c_double]
# Initialize esmini RoadManger with given OpenDRIVE file
odr = '../../../resources/xodr/straight_500m.xodr'
if rm.RM_Init(odr.encode()) == -1: # encode() converts string to pure byte array
print("Failed to load OpenDRIVE file ", )
sys.exit(-1)
rm_pos = rm.RM_CreatePosition() # create a position object, returns a handle
rm_pos_data = RM_PositionData() # object that will be passed and filled in with position info
# test a few positions
x = 65
y = -1.7
rm.RM_SetWorldPosition(rm_pos, x, y, 0.0, 0.0, 0.0, 0.0)
rm.RM_GetPositionData(rm_pos, ct.byref(rm_pos_data))
print('road_id {} lane_id {} lane_offset {:.2f} s {:.2f}'.format(
rm_pos_data.road_id, rm_pos_data.lane_id, rm_pos_data.lane_offset, rm_pos_data.s))
road_id = 1
lane_id = 1
lane_offset = -0.2
s = 40
rm.RM_SetLanePosition(rm_pos, road_id, lane_id, lane_offset, s)
rm.RM_GetPositionData(rm_pos, ct.byref(rm_pos_data))
print('x {:.2f} y {:.2f} h (yaw) {:.2f}'.format(
rm_pos_data.x, rm_pos_data.y, rm_pos_data.h))
Storyboard element state callback
The following code shows how to get notification of storyboard events using StoryBoardElementStateChangeCallback.
# Storyboard element types (see OSCTypeDefs/OSCAction.hpp)
sbe_type = {
0:"UNDEFINED_ELEMENT_TYPE",
1:"STORY_BOARD",
2:"STORY",
3:"ACT",
4:"MANEUVER_GROUP",
5:"MANEUVER",
6:"EVENT",
7:"ACTION"
}
# Storyboard element states (see OSCTypeDefs/OSCAction.hpp)
sbe_state = {
0:"UNDEFINED_ELEMENT_STATE",
1:"STANDBY",
2:"RUNNING",
3:"COMPLETE"
}
# Define callback for scenario storyboard element state changes
# according to function type: void (*fnPtr)(const char* name, int type, int state)
# required by SE_RegisterStoryBoardElementStateChangeCallback()
def callback(name, type, state, full_path):
# just print the received info
print(type)
print("callback: {} ({}) state: {} full path: {}".format(codecs.decode(name), sbe_type[type], sbe_state[state], codecs.decode(full_path), ))
callback_type = ct.CFUNCTYPE(None, ct.c_char_p, ct.c_int, ct.c_int, ct.c_char_p)
callback_func = callback_type(callback)
# Initialize esmini before register the callback
se.SE_AddPath(b"../../../resources/xosc") # search path if run from original location
se.SE_Init(b"../resources/xosc/cut-in.xosc", 0, 1, 0, 1)
# register the callback function
se.SE_RegisterStoryBoardElementStateChangeCallback(callback_func)
OSI groundtruth
OSI groundtruth can also be retrieved and processed via Python. The following code shows one way of doing it. This example also shows how the simulation can be encapsulated in a class.
'''
demonstrate how to fetch OSI data from esmini in Python context
Python dependencies:
pip install protobuf==3.20.2
Note: No need to install OSI as long as esmini/scripts/osi3 folder is available
Instruction:
- make sure the esmini shared library (esminiLib.dll or esminiLib.so) is present in esmini/bin folder
- if not, either compile esmini (see User guide) or fetch bin package release
- from this folder (where this code module is), run: python ./osi_groundtruth.py
'''
import os
import sys
import ctypes as ct
# Add scripts root directory to module search path in order to find osi3
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '../../../', 'scripts')))
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '..', 'scripts'))) # if script moved to Hello World folder
from osi3.osi_groundtruth_pb2 import GroundTruth
# Import esmini lib
if sys.platform == "linux" or sys.platform == "linux2":
se = ct.CDLL("../../../bin/libesminiLib.so")
elif sys.platform == "darwin":
se = ct.CDLL("../../../bin/libesminiLib.dylib")
elif sys.platform == "win32":
se = ct.CDLL("../../../bin/esminiLib.dll")
else:
print("Unsupported platform: {}".format(platform))
quit()
# Specify argument and return types of some esmini functions
se.SE_GetOSIGroundTruth.restype = ct.c_void_p
se.SE_GetOSIGroundTruth.argtypes = [ct.c_void_p]
se.SE_StepDT.argtypes = [ct.c_double]
class Sim:
def __init__(self, scenario):
self.msg = GroundTruth() # OSI groundtruth message
self.msg_size = ct.c_int()
if se.SE_Init(scenario, 0, 1, 0, 0) != 0:
print('Failed to open ', scenario)
exit(-1)
self.GetAndPrintOSIInfo() # Initial state
# Retrieve OSI message and print some info
def GetAndPrintOSIInfo(self):
msg_string = se.SE_GetOSIGroundTruth(ct.byref(self.msg_size))
self.msg.ParseFromString(ct.string_at(msg_string, self.msg_size))
# Print some info
print("Timestamp: {:.2f}".format(self.msg.timestamp.seconds + 1e-9 * self.msg.timestamp.nanos))
for j, o in enumerate(self.msg.moving_object):
print(' Object[{}] id {}'.format(j, o.id.value))
print(' pos.x {:.2f} pos.y {:.2f} rot.h {:.2f}'.format(\
o.base.position.x,\
o.base.position.y,\
o.base.orientation.yaw))
print(' vel.x {:.2f} vel.y {:.2f} rot_rate.h {:.2f}'.format(\
o.base.velocity.x,\
o.base.velocity.y,\
o.base.orientation_rate.yaw))
print(' acc.x {:.2f} acc.y {:.2f} rot_acc.h {:.2f}'.format(\
o.base.acceleration.x,\
o.base.acceleration.y,\
o.base.orientation_acceleration.yaw))
def Run(self):
while se.SE_GetQuitFlag() != 1:
se.SE_StepDT(0.05)
self.GetAndPrintOSIInfo() # Updated state
se.SE_Close()
if __name__ == '__main__':
# Execute when the module is not initialized from an import statement.
sim = Sim(b"../resources/xosc/cut-in.xosc")
sim.Run()
Object state callback
Advanced
Controllers and callbacks can also be utilized via Python. Following code drafts how to grab state of the first scenario object and then, in a callback, manipulate it and report back. If used in combination with ExternalController in mode=additive the scenario action are applied first. On the contrary, if used with mode=override, the scenario actions will not be applied giving exclusive control to the external callback function.
# Definition of SE_ScenarioObjectState struct
class SEScenarioObjectState(ct.Structure):
_fields_ = [
("id", ct.c_int),
("model_id", ct.c_int),
("control", ct.c_int),
("timestamp", ct.c_double),
("x", ct.c_double),
("y", ct.c_double),
("z", ct.c_double),
("h", ct.c_double),
("p", ct.c_double),
("r", ct.c_double),
("roadId", ct.c_int),
("junctionId", ct.c_int),
("t", ct.c_double),
("laneId", ct.c_int),
("laneOffset", ct.c_double),
("s", ct.c_double),
("speed", ct.c_double),
("centerOffsetX", ct.c_double),
("centerOffsetY", ct.c_double),
("centerOffsetZ", ct.c_double),
("width", ct.c_double),
("length", ct.c_double),
("height", ct.c_double),
("objectType", ct.c_int),
("objectCategory", ct.c_int),
("wheel_angle", ct.c_double),
("wheel_rot", ct.c_double),
]
# Define callback for scenario object enabling manipulating the state AFTER scenario step but BEFORE OSI output
# Use in combination with ExternalController in mode=additive in order for scenario actions to be applied first
def callback(state_ptr, b):
state = state_ptr.contents
print("callback for obj {}: x={:.2f} y={:.2f} h={:.2f}".format(state.id, state.x, state.y, state.h))
se.SE_ReportObjectPosXYH(ct.c_int(state.id), ct.c_double(state.x + 0.02), ct.c_double(state.y), ct.c_double(state.h + 0.001))
callback_type = ct.CFUNCTYPE(None, ct.POINTER(SEScenarioObjectState), ct.c_void_p)
callback_func = callback_type(callback)
# Initialize esmini before register the callback
se.SE_AddPath(b"../../../resources/xosc") # search path if run from original location
se.SE_Init(b"../resources/xosc/cut-in.xosc", 0, 1, 0, 1)
# register callback for first object (id=0)
se.SE_RegisterObjectCallback(0, callback_func, 0)
C# binding
A C# wrapper for the esminiLib is provided (ESMiniWrapper.cs). Coverage is limited, but it might serve as a good starting point.
OSI groundtruth with C#
using System;
using System.Runtime.InteropServices;
using ESMini;
using Google.Protobuf;
using static Osi3.GroundTruth;
namespace esmini_csharp
{
class Program
{
static void Main(string[] args)
{
// initialize esmini
if (ESMiniLib.SE_Init("../resources/xosc/cut-in.xosc", 0, 1, 0, 0) != 0)
{
Console.WriteLine("failed to load scenario");
return;
}
int size = 0;
while (ESMiniLib.SE_GetQuitFlag() != 1)
{
// Step esmini
ESMiniLib.SE_Step();
// Get OSI message
IntPtr int_ptr = ESMiniLib.SE_GetOSIGroundTruth(ref size);
Byte[] byte_array = new Byte[size];
Marshal.Copy(int_ptr, byte_array, 0, size);
Osi3.GroundTruth gt_msg = Osi3.GroundTruth.Parser.ParseFrom(byte_array);
// Write some info from OSI message
Console.WriteLine("Time: {0:N3}", gt_msg.Timestamp.Seconds + 1e-9 * gt_msg.Timestamp.Nanos);
foreach (Osi3.MovingObject o in gt_msg.MovingObject)
{
Console.WriteLine(" Object[{0}], Pos: {1:N2}, {2:N2}, {3:N2}",
o.Id.Value, o.Base.Position.X, o.Base.Position.Y, o.Base.Position.Z);
}
}
}
}
}
This example shows, one way, how to access OSI data in a C# environment.
It’s dependent on the ESMiniWrapper.cs, and targeting Windows environment. If the wrapper is modified to work on Linux (referring .so instead of DLL) it might work there as well, but it’s not been tested.
Build
mkdir build
cd build
cmake ..
cmake --build . --config Release
Run
To have the correct relative path to the scenario file and also access to esminiLib we move into esmini/bin folder for running the example.
cd ../../../../bin
../EnvironmentSimulator/code-examples/osi-groundtruth-cs/build/Release/osi-groundtruth
How to create the osi3 C# files
For this example the osi3 C# files were provided. If you need or want to compile them yourself:
-
Get protoc compiler
Suggested version: 3.15.2
Either build it yourself or getprotoc-3.15.2-win64.zipfrom release:
https://github.com/protocolbuffers/protobuf/releases/tag/v3.15.2 -
Get OSI
https://github.com/OpenSimulationInterface/open-simulation-interface/releases/tag/v3.5.0 -
OSI proto files need to be converted for protobuf v3. This is easily done with the provided script:
./convert-to-proto3.sh -
Compile for C#
-
open a command line in
open-simulation-interfaceroot folder -
c:\my_path_to_protoc\protoc.exe *.proto --csharp_out=.
will create C# versions of all proto files
-