Skip to content

Commit 4ee4707

Browse files
s-azumikmiya
andauthored
Ros2 v0.8.0 map based prediction (autowarefoundation#299)
* restore file name for v0.8.0 update Signed-off-by: Azumi Suzuki <azumi.suzuki@tier4.jp> * fix typos in perception (autowarefoundation#862) * Revert "restore file name for v0.8.0 update" This reverts commit 47ab860adfd6664193b741c61f976eee86c5267a. * restore the return type of a function Signed-off-by: Azumi Suzuki <azumi.suzuki@tier4.jp> * delete commented out line Signed-off-by: Azumi Suzuki <azumi.suzuki@tier4.jp> Co-authored-by: Kazuki Miyahara <kmiya@outlook.com>
1 parent e6c11ba commit 4ee4707

File tree

2 files changed

+13
-14
lines changed

2 files changed

+13
-14
lines changed

perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -230,10 +230,10 @@ bool MapBasedPrediction::getPredictedPath(
230230
1 / (2 * std::pow(t, 3));
231231

232232
double target_d_velocity = current_d_velocity;
233-
double target_d_accerelation = 0;
233+
double target_d_acceleration = 0;
234234
Eigen::Vector3d b_3;
235235
b_3 << target_d_position - current_d_position - current_d_velocity * t,
236-
target_d_velocity - current_d_velocity, target_d_accerelation;
236+
target_d_velocity - current_d_velocity, target_d_acceleration;
237237

238238
Eigen::Vector3d x_3;
239239
x_3 = a_3_inv * b_3;
@@ -323,6 +323,6 @@ void MapBasedPrediction::getLinearPredictedPath(
323323
double MapBasedPrediction::calculateLikelihood(const double current_d)
324324
{
325325
double d_std = 0.5;
326-
double likelyhood = std::abs(current_d) / d_std;
327-
return likelyhood;
326+
double likelihood = std::abs(current_d) / d_std;
327+
return likelihood;
328328
}

perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction_ros.cpp

+9-10
Original file line numberDiff line numberDiff line change
@@ -239,8 +239,8 @@ void MapBasedPredictionROS::objectsCallback(
239239
return;
240240
}
241241

242-
autoware_perception_msgs::msg::DynamicObjectArray tmp_objects_whitout_map;
243-
tmp_objects_whitout_map.header = in_objects->header;
242+
autoware_perception_msgs::msg::DynamicObjectArray tmp_objects_without_map;
243+
tmp_objects_without_map.header = in_objects->header;
244244
DynamicObjectWithLanesArray prediction_input;
245245
prediction_input.header = in_objects->header;
246246

@@ -258,9 +258,8 @@ void MapBasedPredictionROS::objectsCallback(
258258
if (
259259
object.semantic.type != autoware_perception_msgs::msg::Semantic::CAR &&
260260
object.semantic.type != autoware_perception_msgs::msg::Semantic::BUS &&
261-
object.semantic.type != autoware_perception_msgs::msg::Semantic::TRUCK)
262-
{
263-
tmp_objects_whitout_map.objects.push_back(tmp_object.object);
261+
object.semantic.type != autoware_perception_msgs::msg::Semantic::TRUCK) {
262+
tmp_objects_without_map.objects.push_back(tmp_object.object);
264263
continue;
265264
}
266265

@@ -278,7 +277,7 @@ void MapBasedPredictionROS::objectsCallback(
278277
tf2::doTransform(
279278
point_orig, debug_point,
280279
debug_map2lidar_transform);
281-
tmp_objects_whitout_map.objects.push_back(object);
280+
tmp_objects_without_map.objects.push_back(object);
282281
continue;
283282
}
284283

@@ -351,7 +350,7 @@ void MapBasedPredictionROS::objectsCallback(
351350
tf2::doTransform(
352351
point_orig, debug_point,
353352
debug_map2lidar_transform);
354-
tmp_objects_whitout_map.objects.push_back(object);
353+
tmp_objects_without_map.objects.push_back(object);
355354
continue;
356355
}
357356

@@ -369,8 +368,8 @@ void MapBasedPredictionROS::objectsCallback(
369368
// add if not yet having lanelet_id
370369
for (const auto & current_uid : lanelet_ids) {
371370
bool is_redundant = false;
372-
for (const auto & chached_uid : uuid2laneids_.at(uid_string)) {
373-
if (chached_uid == current_uid) {
371+
for (const auto & cached_uid : uuid2laneids_.at(uid_string)) {
372+
if (cached_uid == current_uid) {
374373
is_redundant = true;
375374
break;
376375
}
@@ -426,7 +425,7 @@ void MapBasedPredictionROS::objectsCallback(
426425
output.objects = out_objects_in_map;
427426

428427
std::vector<autoware_perception_msgs::msg::DynamicObject> out_objects_without_map;
429-
map_based_prediction_->doLinearPrediction(tmp_objects_whitout_map, out_objects_without_map);
428+
map_based_prediction_->doLinearPrediction(tmp_objects_without_map, out_objects_without_map);
430429
output.objects.insert(
431430
output.objects.begin(), out_objects_without_map.begin(), out_objects_without_map.end());
432431
pub_objects_->publish(output);

0 commit comments

Comments
 (0)