Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(map_based_prediction): prefix map based prediction #7391

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

<group if="$(var use_vector_map)">
<set_remap from="objects" to="/perception/object_recognition/objects"/>
<include file="$(find-pkg-share map_based_prediction)/launch/map_based_prediction.launch.xml">
<include file="$(find-pkg-share autoware_map_based_prediction)/launch/map_based_prediction.launch.xml">
<arg name="output_topic" value="/perception/object_recognition/objects"/>
<arg name="input_topic" value="$(var input/objects)"/>
<arg name="param_path" value="$(var object_recognition_prediction_map_based_prediction_param_path)"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(map_based_prediction)
project(autoware_map_based_prediction)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -22,7 +22,7 @@ ament_auto_add_library(map_based_prediction_node SHARED
target_link_libraries(map_based_prediction_node glog::glog)

rclcpp_components_register_node(map_based_prediction_node
PLUGIN "map_based_prediction::MapBasedPredictionNode"
PLUGIN "autoware::map_based_prediction::MapBasedPredictionNode"
EXECUTABLE map_based_prediction
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
#include <utility>
#include <vector>

namespace map_based_prediction
namespace autoware::map_based_prediction
{
struct LateralKinematicsToLanelet
{
Expand Down Expand Up @@ -416,6 +416,6 @@ class MapBasedPredictionNode : public rclcpp::Node
return true;
};
};
} // namespace map_based_prediction
} // namespace autoware::map_based_prediction

#endif // MAP_BASED_PREDICTION__MAP_BASED_PREDICTION_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include <utility>
#include <vector>

namespace map_based_prediction
namespace autoware::map_based_prediction
{
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObject;
Expand Down Expand Up @@ -145,6 +145,6 @@ class PathGenerator
const TrackedObject & object, const PosePath & ref_path, const double duration,
const double speed_limit = 0.0) const;
};
} // namespace map_based_prediction
} // namespace autoware::map_based_prediction

#endif // MAP_BASED_PREDICTION__PATH_GENERATOR_HPP_
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<launch>
<arg name="param_path" default="$(find-pkg-share map_based_prediction)/config/map_based_prediction.param.yaml"/>
<arg name="param_path" default="$(find-pkg-share autoware_map_based_prediction)/config/map_based_prediction.param.yaml"/>

<arg name="vector_map_topic" default="/map/vector_map"/>
<arg name="traffic_signals_topic" default="/perception/traffic_light_recognition/traffic_signals"/>
<arg name="output_topic" default="objects"/>
<arg name="input_topic" default="/perception/object_recognition/tracking/objects"/>

<node pkg="map_based_prediction" exec="map_based_prediction" name="map_based_prediction" output="screen">
<node pkg="autoware_map_based_prediction" exec="map_based_prediction" name="map_based_prediction" output="screen">
<param from="$(var param_path)"/>
<remap from="/vector_map" to="$(var vector_map_topic)"/>
<remap from="/traffic_signals" to="$(var traffic_signals_topic)"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>map_based_prediction</name>
<name>autoware_map_based_prediction</name>
<version>0.1.0</version>
<description>This package implements a map_based_prediction</description>
<maintainer email="[email protected]">Tomoya Kimura</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "map_based_prediction/map_based_prediction_node.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"

namespace map_based_prediction
namespace autoware::map_based_prediction
{
visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker(
const TrackedObject & object, const Maneuver & maneuver, const size_t obj_num)
Expand Down Expand Up @@ -46,4 +46,4 @@ visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker(

return marker;
}
} // namespace map_based_prediction
} // namespace autoware::map_based_prediction
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@
#include <functional>
#include <limits>

namespace map_based_prediction
namespace autoware::map_based_prediction
{

namespace
Expand Down Expand Up @@ -2495,7 +2495,7 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal(
return true;
}

} // namespace map_based_prediction
} // namespace autoware::map_based_prediction

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(map_based_prediction::MapBasedPredictionNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_based_prediction::MapBasedPredictionNode)
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <algorithm>

namespace map_based_prediction
namespace autoware::map_based_prediction
{
PathGenerator::PathGenerator(
const double sampling_time_interval, const double min_crosswalk_user_velocity)
Expand Down Expand Up @@ -487,4 +487,4 @@ FrenetPoint PathGenerator::getFrenetPoint(

return frenet_point;
}
} // namespace map_based_prediction
} // namespace autoware::map_based_prediction
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,9 @@ TEST(PathGenerator, test_generatePathForNonVehicleObject)
const double prediction_time_horizon = 10.0;
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate pedestrian object
TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN);
Expand All @@ -77,8 +78,9 @@ TEST(PathGenerator, test_generatePathForLowSpeedVehicle)
const double prediction_time_horizon = 10.0;
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate dummy object
TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR);
Expand All @@ -100,8 +102,9 @@ TEST(PathGenerator, test_generatePathForOffLaneVehicle)
const double prediction_time_horizon = 10.0;
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate dummy object
TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR);
Expand All @@ -123,14 +126,15 @@ TEST(PathGenerator, test_generatePathForOnLaneVehicle)
const double lateral_control_time_horizon = 5.0;
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate dummy object
TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR);

// Generate reference path
map_based_prediction::PosePath ref_paths;
autoware::map_based_prediction::PosePath ref_paths;
geometry_msgs::msg::Pose pose;
pose.position.x = 0.0;
pose.position.y = 0.0;
Expand All @@ -154,14 +158,15 @@ TEST(PathGenerator, test_generatePathForCrosswalkUser)
const double prediction_time_horizon = 10.0;
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate dummy object
TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN);

// Generate dummy crosswalk
map_based_prediction::CrosswalkEdgePoints reachable_crosswalk;
autoware::map_based_prediction::CrosswalkEdgePoints reachable_crosswalk;
reachable_crosswalk.front_center_point << 0.0, 0.0;
reachable_crosswalk.front_right_point << 1.0, 0.0;
reachable_crosswalk.front_left_point << -1.0, 0.0;
Expand All @@ -185,8 +190,9 @@ TEST(PathGenerator, test_generatePathToTargetPoint)
// Generate Path generator
const double prediction_sampling_time_interval = 0.5;
const double min_crosswalk_user_velocity = 0.1;
const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);
const autoware::map_based_prediction::PathGenerator path_generator =
autoware::map_based_prediction::PathGenerator(
prediction_sampling_time_interval, min_crosswalk_user_velocity);

// Generate dummy object
TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR);
Expand Down
Loading