Skip to content

Commit

Permalink
Ros2 v0.8.0 map based prediction (autowarefoundation#299)
Browse files Browse the repository at this point in the history
* 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>
  • Loading branch information
s-azumi and kmiya authored Feb 2, 2021
1 parent e6c11ba commit 4ee4707
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -230,10 +230,10 @@ bool MapBasedPrediction::getPredictedPath(
1 / (2 * std::pow(t, 3));

double target_d_velocity = current_d_velocity;
double target_d_accerelation = 0;
double target_d_acceleration = 0;
Eigen::Vector3d b_3;
b_3 << target_d_position - current_d_position - current_d_velocity * t,
target_d_velocity - current_d_velocity, target_d_accerelation;
target_d_velocity - current_d_velocity, target_d_acceleration;

Eigen::Vector3d x_3;
x_3 = a_3_inv * b_3;
Expand Down Expand Up @@ -323,6 +323,6 @@ void MapBasedPrediction::getLinearPredictedPath(
double MapBasedPrediction::calculateLikelihood(const double current_d)
{
double d_std = 0.5;
double likelyhood = std::abs(current_d) / d_std;
return likelyhood;
double likelihood = std::abs(current_d) / d_std;
return likelihood;
}
Original file line number Diff line number Diff line change
Expand Up @@ -239,8 +239,8 @@ void MapBasedPredictionROS::objectsCallback(
return;
}

autoware_perception_msgs::msg::DynamicObjectArray tmp_objects_whitout_map;
tmp_objects_whitout_map.header = in_objects->header;
autoware_perception_msgs::msg::DynamicObjectArray tmp_objects_without_map;
tmp_objects_without_map.header = in_objects->header;
DynamicObjectWithLanesArray prediction_input;
prediction_input.header = in_objects->header;

Expand All @@ -258,9 +258,8 @@ void MapBasedPredictionROS::objectsCallback(
if (
object.semantic.type != autoware_perception_msgs::msg::Semantic::CAR &&
object.semantic.type != autoware_perception_msgs::msg::Semantic::BUS &&
object.semantic.type != autoware_perception_msgs::msg::Semantic::TRUCK)
{
tmp_objects_whitout_map.objects.push_back(tmp_object.object);
object.semantic.type != autoware_perception_msgs::msg::Semantic::TRUCK) {
tmp_objects_without_map.objects.push_back(tmp_object.object);
continue;
}

Expand All @@ -278,7 +277,7 @@ void MapBasedPredictionROS::objectsCallback(
tf2::doTransform(
point_orig, debug_point,
debug_map2lidar_transform);
tmp_objects_whitout_map.objects.push_back(object);
tmp_objects_without_map.objects.push_back(object);
continue;
}

Expand Down Expand Up @@ -351,7 +350,7 @@ void MapBasedPredictionROS::objectsCallback(
tf2::doTransform(
point_orig, debug_point,
debug_map2lidar_transform);
tmp_objects_whitout_map.objects.push_back(object);
tmp_objects_without_map.objects.push_back(object);
continue;
}

Expand All @@ -369,8 +368,8 @@ void MapBasedPredictionROS::objectsCallback(
// add if not yet having lanelet_id
for (const auto & current_uid : lanelet_ids) {
bool is_redundant = false;
for (const auto & chached_uid : uuid2laneids_.at(uid_string)) {
if (chached_uid == current_uid) {
for (const auto & cached_uid : uuid2laneids_.at(uid_string)) {
if (cached_uid == current_uid) {
is_redundant = true;
break;
}
Expand Down Expand Up @@ -426,7 +425,7 @@ void MapBasedPredictionROS::objectsCallback(
output.objects = out_objects_in_map;

std::vector<autoware_perception_msgs::msg::DynamicObject> out_objects_without_map;
map_based_prediction_->doLinearPrediction(tmp_objects_whitout_map, out_objects_without_map);
map_based_prediction_->doLinearPrediction(tmp_objects_without_map, out_objects_without_map);
output.objects.insert(
output.objects.begin(), out_objects_without_map.begin(), out_objects_without_map.end());
pub_objects_->publish(output);
Expand Down

0 comments on commit 4ee4707

Please sign in to comment.