targetPoses
Get positions and orientations of targets in sensor range relative to host vehicle
Since R2023a
Description
Examples
Add Sensors to RoadRunner Scenario Using MATLAB
Define sensor models in MATLAB®, and add them to vehicle actors in a RoadRunner Scenario. Then, obtain ground truth measurements from RoadRunner Scenario, process them into detections for visualization.
Set Up RoadRunner Scenario — MATLAB Interface
Configure your RoadRunner installation and project folder properties. Open the RoadRunner app.
rrInstallationPath = "C:\Program Files\RoadRunner R2024a\bin\win64"; rrProjectPath = "D:\RR\TestProjects"; s = settings; s.roadrunner.application.InstallationFolder.PersonalValue = rrInstallationPath; rrApp = roadrunner(rrProjectPath);
To open the scenario this example uses, you must add the TrajectoryCutIn-longRun.rrscenario
file from the example folder to your RoadRunner project folder. Then, open the scenario.
copyfile("TrajectoryCutIn-longRun.rrscenario",fullfile(rrProjectPath,"Scenarios/")) openScenario(rrApp,"TrajectoryCutIn-longRun")
Create a ScenarioSimulation
object to connect MATLAB to the RoadRunner Scenario simulation and set the step size.
scenarioSim = createSimulation(rrApp);
stepSize = 0.1;
set(scenarioSim,"StepSize",stepSize);
Create a SensorSimulation
object to control the sensor configuration for the RoadRunner Scenario simulation.
sensorSim = get(scenarioSim,"SensorSimulation");
Configure Sensors and Add to RoadRunner Scenario
Configure sensor models for vision, radar and lidar sensors to add to the ego vehicle using visionDetectionGenerator
, drivingRadarDataGenerator
and lidarPointCloudGenerator
objects. Specify unique IDs for each sensor.
visionSensor = visionDetectionGenerator(SensorIndex=1, ... SensorLocation=[2.4 0], MaxRange=50, ... DetectorOutput="Lanes and objects", ... UpdateInterval=stepSize); radarSensor = drivingRadarDataGenerator(SensorIndex=2,... MountingLocation=[1.8 0 0.2], FieldOfView=[80 5],... AzimuthResolution=1,UpdateRate=1/stepSize); lidarSensor = lidarPointCloudGenerator(SensorIndex=3,UpdateInterval=stepSize);
Add the sensor to the ego vehicle actor in the RoadRunner scenario. Specify the Actor
ID
property for the vehicle.
egoVehicleID = 1; addSensors(sensorSim,{visionSensor,radarSensor,lidarSensor},egoVehicleID);
Set up bird's-eye-plot for visualization.
[visionDetPlotter,radarDetPlotter,pcPlotter,lbGTPlotter,lbDetPlotter,bepAxes] = helperSetupBEP(visionSensor,radarSensor);
Simulate RoadRunner Scenario and Visualize Sensor Data
Use the ScenarioSimulation
object to step through the RoadRunner scenario. Retrieve target poses in the sensor range using the targetPoses
function, and process them into detections using the sensor model. Visualize detections and ground truth lane boundaries using birdsEyePlot
.
simTime = 0.0; set(scenarioSim,"SimulationCommand","Step"); pause(0.1) legend(bepAxes,"show") while ~isequal(get(scenarioSim,"SimulationStatus"),"Stopped") % Get ground truth target poses and lane boundaries from the sensor tgtPoses = targetPoses(sensorSim,1); gTruthLbs = laneBoundaries(sensorSim,1,OutputOption="EgoAdjacentLanes",inHostCoordinate=true); if ~isempty(gTruthLbs) % Get detections from vision and radar sensors [visionDets,numVisionDets,visionDetsValid,lbDets,numLbDets,lbDetsValid] = visionSensor(tgtPoses,gTruthLbs,simTime); [radarDets,numRadarDets,radarDetsValid] = radarSensor(tgtPoses,simTime); % Get point cloud from lidar sensor [ptCloud,ptCloudValid] = lidarSensor(); % Plot ground-truth and detected lane boundaries helperPlotLaneBoundaries(lbGTPlotter,gTruthLbs) % Plot vision and radar detections if visionDetsValid detPos = cellfun(@(d)d.Measurement(1:2),visionDets,UniformOutput=false); detPos = vertcat(zeros(0,2),cell2mat(detPos')'); plotDetection(visionDetPlotter,detPos) end if lbDetsValid plotLaneBoundary(lbDetPlotter,vertcat(lbDets.LaneBoundaries)) end if radarDetsValid detPos = cellfun(@(d)d.Measurement(1:2),radarDets,UniformOutput=false); detPos = vertcat(zeros(0,2),cell2mat(detPos')'); plotDetection(radarDetPlotter,detPos) end % Plot lidar point cloud if ptCloudValid plotPointCloud(pcPlotter,ptCloud); end end if ~isequal(get(scenarioSim,"SimulationStatus"),"Stopped") set(scenarioSim,"SimulationCommand","Step"); end simTime = simTime + stepSize; pause(0.1) end
Helper Functions
helperSetupBEP
function creates a bird's-eye-plot and configures all the plotters for visualization.
helperPlotLaneBoundaries
function plots the lane boundaries on the birds'eye-plot.
Input Arguments
sensorSim
— Sensor simulation object
SensorSimulation
object
Sensor simulation object, specified as a SensorSimulation
object. The sensor simulation object must correspond to the
desired scenario created in RoadRunner Scenario.
sensorID
— Unique index of sensor in RoadRunner scenario
positive integer
Unique index of the sensor in the RoadRunner scenario, specified as a positive integer. This must be same as the
SensorIndex
property of the detection generator object that
corresponds to the desired sensor.
Output Arguments
poses
— Target poses
structure | array of structures
Target poses, in ego vehicle coordinates, returned as a structure or as an array of structures. This output does not include the pose of the host vehicle actor.
A target pose defines the position, velocity, and orientation of a target in ego vehicle coordinates. Target poses also include the rates of change in actor position and orientation.
Each pose structure has these fields.
Field | Description |
---|---|
ActorID | Scenario-defined actor identifier, returned as a positive integer. |
ClassID | Classification identifier, returned as a nonnegative integer.
0 represents an object of an unknown or unassigned
class. |
Position | Position of actor, returned as a real-valued vector of the form [x y z]. Units are in meters. |
Velocity | Velocity (v) of actor in the x-, y-, and z-directions, returned as a real-valued vector of the form [vx vy vz]. Units are in meters per second. |
Roll | Roll angle of actor, returned as a real scalar. Units are in degrees. |
Pitch | Pitch angle of actor, returned as a real scalar. Units are in degrees. |
Yaw | Yaw angle of actor, returned as a real scalar. Units are in degrees. |
AngularVelocity | Angular velocity (ω) of actor in the x-, y-, and z-directions, returned as a real-valued vector of the form [ωx ωy ωz]. Units are in degrees per second. |
For full definitions of these structure fields, see the actor
and vehicle
functions.
Version History
Introduced in R2023a
See Also
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)