Skip to content

Commit 02c0516

Browse files
Add node for radar object tracking (#280)
* Add radar object tracking node and test placeholders. Signed-off-by: Paweł Liberadzki <[email protected]> * Add test for basic node run. Signed-off-by: Paweł Liberadzki <[email protected]> * Add first implementation for detections clusterization. Signed-off-by: Paweł Liberadzki <[email protected]> * Add working detections clusterization. Signed-off-by: Paweł Liberadzki <[email protected]> * Add complete debug test. Make minor cleanup in node implementation. Signed-off-by: Paweł Liberadzki <[email protected]> * Add milliseconds cast to helper Time structure. Signed-off-by: Paweł Liberadzki <[email protected]> * Add disabling Vector initializer list constructor, when there is only one dimension. Signed-off-by: Paweł Liberadzki <[email protected]> * Add RunningStats helper structer for running mean and standard deviation. Signed-off-by: Paweł Liberadzki <[email protected]> * Add basic object state handling to RadarTrackObjectsNode. Signed-off-by: Paweł Liberadzki <[email protected]> * Add fixed objects count test. Make some cleanup in object tracking tests. Signed-off-by: Paweł Liberadzki <[email protected]> * Fix ROS 2 for radar track objects test. Signed-off-by: Paweł Liberadzki <[email protected]> * Update local constants to be node parameters. Add API call documentation for object tracking. Signed-off-by: Paweł Liberadzki <[email protected]> * Update object tracking node documentation with parameter units. Signed-off-by: Paweł Liberadzki <[email protected]> * Make changes according to review for #280. Signed-off-by: Paweł Liberadzki <[email protected]> --------- Signed-off-by: Paweł Liberadzki <[email protected]>
1 parent f0ce4bf commit 02c0516

File tree

12 files changed

+527
-3
lines changed

12 files changed

+527
-3
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,7 @@ set(RGL_SOURCE_FILES
123123
src/graph/FromMat3x4fRaysNode.cpp
124124
src/graph/FilterGroundPointsNode.cpp
125125
src/graph/RadarPostprocessPointsNode.cpp
126+
src/graph/RadarTrackObjectsNode.cpp
126127
src/graph/SetRangeRaysNode.cpp
127128
src/graph/SetRaysRingIdsRaysNode.cpp
128129
src/graph/SetTimeOffsetsRaysNode.cpp

include/rgl/api/core.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -828,6 +828,24 @@ RGL_API rgl_status_t rgl_node_points_radar_postprocess(rgl_node_t* node, const r
828828
float cumulative_device_gain, float received_noise_mean,
829829
float received_noise_st_dev);
830830

831+
/**
832+
* Creates or modifies RadarTrackObjectsNode.
833+
* The Node takes radar detections point cloud as input (from rgl_node_points_radar_postprocess), groups detections into objects based on given thresholds (node parameters),
834+
* and calculates various characteristics of these objects. This Node is intended to be connected to object list publishing node (from rgl_node_publish_udp_objectlist).
835+
* The output from this Node is in the form of a point cloud, where point XYZ coordinates are tracked objects positions.
836+
* Note that for correct calculation and publishing some of object characteristics (e.g. velocity) user has to call rgl_scene_set_time for current scene.
837+
* Graph input: point cloud, containing RGL_FIELD_DISTANCE_F32, RGL_FIELD_AZIMUTH_F32, RGL_FIELD_ELEVATION_F32 and RGL_FIELD_RADIAL_SPEED_F32
838+
* Graph output: point cloud
839+
* @param node If (*node) == nullptr, a new Node will be created. Otherwise, (*node) will be modified.
840+
* @param object_distance_threshold The maximum distance between a radar detection and other closest detection classified as the same tracked object (in meters).
841+
* @param object_azimuth_threshold The maximum azimuth difference between a radar detection and other closest detection classified as the same tracked object (in radians).
842+
* @param object_elevation_threshold The maximum elevation difference between a radar detection and other closest detection classified as the same tracked object (in radians).
843+
* @param object_radial_speed_threshold The maximum radial speed difference between a radar detection and other closest detection classified as the same tracked object (in meters per second).
844+
*/
845+
RGL_API rgl_status_t rgl_node_points_radar_track_objects(rgl_node_t* node, float object_distance_threshold,
846+
float object_azimuth_threshold, float object_elevation_threshold,
847+
float object_radial_speed_threshold);
848+
831849
/**
832850
* Creates or modifies FilterGroundPointsNode.
833851
* The Node adds RGL_FIELD_IS_GROUND_I32 which indicates the point is on the ground. Points are not removed.

src/Time.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ struct Time
3131
static Time nanoseconds(uint64_t nanoseconds) { return Time(nanoseconds); }
3232

3333
HostDevFn double asSeconds() const { return static_cast<double>(timeNs) * 1.0e-9; };
34+
HostDevFn double asMilliseconds() const { return static_cast<double>(timeNs) * 1.0e-6; };
3435
HostDevFn uint64_t asNanoseconds() const { return timeNs; }
3536

3637
#if RGL_BUILD_ROS2_EXTENSION

src/api/apiCore.cpp

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1131,6 +1131,38 @@ void TapeCore::tape_node_points_radar_postprocess(const YAML::Node& yamlNode, Pl
11311131
state.nodes.insert({nodeId, node});
11321132
}
11331133

1134+
RGL_API rgl_status_t rgl_node_points_radar_track_objects(rgl_node_t* node, float object_distance_threshold,
1135+
float object_azimuth_threshold, float object_elevation_threshold,
1136+
float object_radial_speed_threshold)
1137+
{
1138+
auto status = rglSafeCall([&]() {
1139+
RGL_API_LOG("rgl_node_points_radar_track_objects(node={}, object_distance_threshold={}, object_azimuth_threshold={}, "
1140+
"object_elevation_threshold={}, object_radial_speed_threshold={})",
1141+
repr(node), object_distance_threshold, object_azimuth_threshold, object_elevation_threshold,
1142+
object_radial_speed_threshold);
1143+
CHECK_ARG(node != nullptr);
1144+
CHECK_ARG(object_distance_threshold > 0.0f);
1145+
CHECK_ARG(object_azimuth_threshold > 0.0f);
1146+
CHECK_ARG(object_elevation_threshold > 0.0f);
1147+
CHECK_ARG(object_radial_speed_threshold > 0.0f);
1148+
1149+
createOrUpdateNode<RadarTrackObjectsNode>(node, object_distance_threshold, object_azimuth_threshold,
1150+
object_elevation_threshold, object_radial_speed_threshold);
1151+
});
1152+
TAPE_HOOK(node, object_distance_threshold, object_azimuth_threshold, object_elevation_threshold,
1153+
object_radial_speed_threshold);
1154+
return status;
1155+
}
1156+
1157+
void TapeCore::tape_node_points_radar_track_objects(const YAML::Node& yamlNode, PlaybackState& state)
1158+
{
1159+
auto nodeId = yamlNode[0].as<TapeAPIObjectID>();
1160+
rgl_node_t node = state.nodes.contains(nodeId) ? state.nodes.at(nodeId) : nullptr;
1161+
rgl_node_points_radar_track_objects(&node, yamlNode[1].as<float>(), yamlNode[2].as<float>(), yamlNode[3].as<float>(),
1162+
yamlNode[4].as<float>());
1163+
state.nodes.insert({nodeId, node});
1164+
}
1165+
11341166
RGL_API rgl_status_t rgl_node_points_filter_ground(rgl_node_t* node, const rgl_vec3f* sensor_up_vector,
11351167
float ground_angle_threshold)
11361168
{

src/graph/NodesCore.hpp

Lines changed: 90 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include <gpu/nodeKernels.hpp>
3131
#include <CacheManager.hpp>
3232
#include <GPUFieldDescBuilder.hpp>
33+
#include <math/RuningStats.hpp>
3334
#include <gpu/MultiReturn.hpp>
3435

3536

@@ -588,6 +589,95 @@ struct RadarPostprocessPointsNode : IPointsNodeSingleInput
588589
};
589590
};
590591

592+
struct RadarTrackObjectsNode : IPointsNodeSingleInput
593+
{
594+
using Ptr = std::shared_ptr<RadarTrackObjectsNode>;
595+
596+
enum class ObjectStatus : uint8_t
597+
{
598+
Measured = 0,
599+
New = 1,
600+
Predicted = 2,
601+
Invalid = 255
602+
};
603+
604+
enum class MovementStatus : uint8_t
605+
{
606+
Moved = 0,
607+
Stationary = 1,
608+
Invalid = 255
609+
};
610+
611+
struct ClassificationProbabilities
612+
{
613+
float existence{100.0f};
614+
uint8_t classCar{0};
615+
uint8_t classTruck{0};
616+
uint8_t classMotorcycle{0};
617+
uint8_t classBicycle{0};
618+
uint8_t classPedestrian{0};
619+
uint8_t classAnimal{0};
620+
uint8_t classHazard{0};
621+
};
622+
623+
struct ObjectState
624+
{
625+
uint32_t id{0};
626+
uint32_t framesCount{0};
627+
uint32_t creationTime{0};
628+
ObjectStatus objectStatus{ObjectStatus::Invalid};
629+
MovementStatus movementStatus{MovementStatus::Invalid};
630+
ClassificationProbabilities classificationProbabilities{};
631+
632+
RunningStats<Vec3f> position{};
633+
RunningStats<float> orientation{};
634+
RunningStats<Vec2f> absVelocity{};
635+
RunningStats<Vec2f> relVelocity{};
636+
RunningStats<Vec2f> absAccel{};
637+
RunningStats<Vec2f> relAccel{};
638+
RunningStats<float> orientationRate{};
639+
RunningStats<float> length{};
640+
RunningStats<float> width{};
641+
};
642+
643+
RadarTrackObjectsNode();
644+
645+
void setParameters(float distanceThreshold, float azimuthThreshold, float elevationThreshold,
646+
float radialSpeedThreshold);
647+
648+
// Node
649+
void validateImpl() override;
650+
void enqueueExecImpl() override;
651+
652+
bool hasField(rgl_field_t field) const override { return fieldData.contains(field); }
653+
654+
// Node requirements
655+
std::vector<rgl_field_t> getRequiredFieldList() const override;
656+
657+
// Data getters
658+
IAnyArray::ConstPtr getFieldData(rgl_field_t field) override { return fieldData.at(field); }
659+
size_t getWidth() const override { return fieldData.empty() ? 0 : fieldData.begin()->second->getCount(); }
660+
size_t getHeight() const override { return 1; } // In fact, this will be only a 1-dimensional array.
661+
662+
const std::list<ObjectState>& getObjectStates() const { return objectStates; }
663+
664+
private:
665+
std::list<ObjectState> objectStates;
666+
std::unordered_map<rgl_field_t, IAnyArray::Ptr> fieldData;
667+
668+
float distanceThreshold;
669+
float azimuthThreshold;
670+
float elevationThreshold;
671+
float radialSpeedThreshold;
672+
673+
HostPinnedArray<Field<XYZ_VEC3_F32>::type>::Ptr xyzHostPtr = HostPinnedArray<Field<XYZ_VEC3_F32>::type>::create();
674+
HostPinnedArray<Field<DISTANCE_F32>::type>::Ptr distanceHostPtr = HostPinnedArray<Field<DISTANCE_F32>::type>::create();
675+
HostPinnedArray<Field<AZIMUTH_F32>::type>::Ptr azimuthHostPtr = HostPinnedArray<Field<AZIMUTH_F32>::type>::create();
676+
HostPinnedArray<Field<ELEVATION_F32>::type>::Ptr elevationHostPtr = HostPinnedArray<Field<ELEVATION_F32>::type>::create();
677+
HostPinnedArray<Field<RADIAL_SPEED_F32>::type>::Ptr radialSpeedHostPtr =
678+
HostPinnedArray<Field<RADIAL_SPEED_F32>::type>::create();
679+
};
680+
591681
struct FilterGroundPointsNode : IPointsNodeSingleInput
592682
{
593683
using Ptr = std::shared_ptr<FilterGroundPointsNode>;
Lines changed: 128 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,128 @@
1+
// Copyright 2024 Robotec.AI
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <graph/NodesCore.hpp>
16+
#include <scene/Scene.hpp>
17+
18+
RadarTrackObjectsNode::RadarTrackObjectsNode() { fieldData.emplace(XYZ_VEC3_F32, createArray<HostPinnedArray>(XYZ_VEC3_F32)); }
19+
20+
void RadarTrackObjectsNode::setParameters(float distanceThreshold, float azimuthThreshold, float elevationThreshold,
21+
float radialSpeedThreshold)
22+
{
23+
this->distanceThreshold = distanceThreshold;
24+
this->azimuthThreshold = azimuthThreshold;
25+
this->elevationThreshold = elevationThreshold;
26+
this->radialSpeedThreshold = radialSpeedThreshold;
27+
}
28+
29+
void RadarTrackObjectsNode::validateImpl() { IPointsNodeSingleInput::validateImpl(); }
30+
31+
void RadarTrackObjectsNode::enqueueExecImpl()
32+
{
33+
xyzHostPtr->copyFrom(input->getFieldData(XYZ_VEC3_F32));
34+
distanceHostPtr->copyFrom(input->getFieldData(DISTANCE_F32));
35+
azimuthHostPtr->copyFrom(input->getFieldData(AZIMUTH_F32));
36+
elevationHostPtr->copyFrom(input->getFieldData(ELEVATION_F32));
37+
radialSpeedHostPtr->copyFrom(input->getFieldData(RADIAL_SPEED_F32));
38+
39+
const int detectionsCount = input->getPointCount();
40+
41+
objectStates.clear(); // TODO(Pawel): Remove this when we start working on tracking.
42+
43+
// Top level in this list is for objects. Bottom level is for detections that belong to specific objects. Below is an initialization of a helper
44+
// structure for region growing, which starts with a while-loop.
45+
std::list<std::list<int>> objectIndices;
46+
for (auto i = 0; i < detectionsCount; ++i) {
47+
objectIndices.emplace_back(1, i);
48+
}
49+
50+
auto leftIndex = 0;
51+
while (leftIndex < objectIndices.size() - 1) {
52+
auto ownIt = objectIndices.begin();
53+
std::advance(ownIt, leftIndex);
54+
auto checkedIt = std::next(ownIt);
55+
bool reorganizationTookPlace = false;
56+
57+
while (checkedIt != objectIndices.end()) {
58+
auto& checkedIndices = *checkedIt;
59+
60+
// TODO(Pawel): In theory, I do not have to check the same indices multiple times when growing this subset in next iterations.
61+
for (auto ownDetectionId : *ownIt) {
62+
const auto isPartOfSameObject = [&, distance = distanceHostPtr->at(ownDetectionId),
63+
azimuth = azimuthHostPtr->at(ownDetectionId),
64+
elevation = elevationHostPtr->at(ownDetectionId),
65+
radialSpeed = radialSpeedHostPtr->at(ownDetectionId)](int checkedDetectionId) {
66+
return std::abs(distanceHostPtr->at(checkedDetectionId) - distance) <= distanceThreshold &&
67+
std::abs(azimuthHostPtr->at(checkedDetectionId) - azimuth) <= azimuthThreshold &&
68+
std::abs(elevationHostPtr->at(checkedDetectionId) - elevation) <= elevationThreshold &&
69+
std::abs(radialSpeedHostPtr->at(checkedDetectionId) - radialSpeed) <= radialSpeedThreshold;
70+
};
71+
72+
if (std::any_of(checkedIndices.cbegin(), checkedIndices.cend(), isPartOfSameObject)) {
73+
ownIt->splice(ownIt->cend(), checkedIndices);
74+
break;
75+
}
76+
}
77+
if (checkedIndices.empty()) {
78+
checkedIt = objectIndices.erase(checkedIt);
79+
reorganizationTookPlace = true;
80+
} else {
81+
++checkedIt;
82+
}
83+
}
84+
85+
if (!reorganizationTookPlace) {
86+
// We are done with growing this object, no more matching detections are available.
87+
++leftIndex;
88+
}
89+
}
90+
91+
fieldData[XYZ_VEC3_F32]->resize(objectIndices.size(), true, false);
92+
auto* xyzPtr = static_cast<Vec3f*>(fieldData[XYZ_VEC3_F32]->getRawWritePtr());
93+
uint32_t objectIndex = 0;
94+
95+
for (const auto& separateObjectIndices : objectIndices) {
96+
auto objectCenter = Vec3f(0.0f, 0.0f, 0.0f);
97+
for (const auto index : separateObjectIndices) {
98+
objectCenter += xyzHostPtr->at(index);
99+
}
100+
101+
auto& objectState = objectStates.emplace_back();
102+
objectState.id = objectIndex++;
103+
objectState.framesCount = 1; // This will be updated with object tracking introduction.
104+
objectState.creationTime = static_cast<uint32_t>(Scene::instance().getTime().value_or(Time::zero()).asMilliseconds());
105+
objectState.objectStatus = ObjectStatus::New;
106+
objectState.movementStatus =
107+
MovementStatus::Invalid; // Newly created object does not have velocity data (no 'previous frame' exists).
108+
objectState.position.addSample(objectCenter / static_cast<float>(separateObjectIndices.size()));
109+
110+
// TODO(Pawel): This will require modyfing radar postprocess node - I will require some bounding box here.
111+
objectState.orientation.addSample(0.0f);
112+
objectState.absVelocity.addSample(Vec2f(0.0f, 0.0f));
113+
objectState.relVelocity.addSample(Vec2f(0.0f, 0.0f));
114+
objectState.absAccel.addSample(Vec2f(0.0f, 0.0f));
115+
objectState.relAccel.addSample(Vec2f(0.0f, 0.0f));
116+
objectState.orientationRate.addSample(0.0f);
117+
objectState.length.addSample(0.0f);
118+
objectState.width.addSample(0.0f);
119+
120+
// TODO(Pawel): Be careful with indexing here, when working on tracking - id will not match the index for not new objects.
121+
xyzPtr[objectState.id] = 1 / static_cast<float>(separateObjectIndices.size()) * objectCenter;
122+
}
123+
}
124+
125+
std::vector<rgl_field_t> RadarTrackObjectsNode::getRequiredFieldList() const
126+
{
127+
return {XYZ_VEC3_F32, DISTANCE_F32, AZIMUTH_F32, ELEVATION_F32, RADIAL_SPEED_F32};
128+
}

src/math/RuningStats.hpp

Lines changed: 74 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,74 @@
1+
// Copyright 2023 Robotec.AI
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#pragma once
16+
17+
// Integral types here generally make no sense in terms of mean and std dev.
18+
// I would force users to use floats, to eliminate possible errors.
19+
template<typename StatType, typename = std::enable_if_t<!std::is_integral_v<StatType>>>
20+
class RunningStats
21+
{
22+
public:
23+
static constexpr RunningStats calculateFor(const std::vector<StatType>& range)
24+
{
25+
RunningStats stats;
26+
for (auto&& element : range) {
27+
stats.addSample(element);
28+
}
29+
return stats;
30+
}
31+
32+
void addSample(StatType sample)
33+
{
34+
++counter;
35+
StatType delta = sample - mean;
36+
mean += delta / counter;
37+
m2 += delta * (sample - mean);
38+
}
39+
40+
StatType getMean() const { return mean; }
41+
42+
StatType getVariance() const { return counter < 2 ? StatType{} : m2 / counter; }
43+
44+
auto getStdDev() const
45+
{
46+
// This if-statement is only for handling floating point numbers.
47+
if constexpr (std::is_floating_point_v<StatType>) {
48+
return std::sqrt(getVariance());
49+
}
50+
51+
// If-statement below all handle Vector types.
52+
const auto variance = getVariance();
53+
54+
if constexpr (std::is_same_v<StatType, Vector<2, float>>) {
55+
return Vector<2, float>{std::sqrt(variance.x()), std::sqrt(variance.y())};
56+
}
57+
58+
if constexpr (std::is_same_v<StatType, Vector<3, float>>) {
59+
return Vector<3, float>{std::sqrt(variance.x()), std::sqrt(variance.y()), std::sqrt(variance.z())};
60+
}
61+
62+
if constexpr (std::is_same_v<StatType, Vector<4, float>>) {
63+
return Vector<4, float>{std::sqrt(variance[0]), std::sqrt(variance[1]), std::sqrt(variance[2]),
64+
std::sqrt(variance[3])};
65+
}
66+
}
67+
68+
auto getMeanAndStdDev() const { return std::make_pair(getMean(), getStdDev()); }
69+
70+
private:
71+
size_t counter{0};
72+
StatType mean{0};
73+
StatType m2{0};
74+
};

src/math/Vector.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,8 @@ struct Vector
4444
Vector(const std::array<T, dim>& values) { std::copy(values.begin(), values.end(), row); }
4545

4646
// List constructor
47-
template<typename... Args>
47+
template<typename... Args,
48+
typename = typename std::enable_if<sizeof...(Args) >= 2>::type>
4849
HostDevFn Vector(Args... args) : row{static_cast<T>(args)...}
4950
{
5051
static_assert(sizeof...(Args) == dim);

0 commit comments

Comments
 (0)