diff --git a/driving_environment_analyzer/launch/driving_environment_analyzer.launch.xml b/driving_environment_analyzer/launch/driving_environment_analyzer.launch.xml index 2ba3e71d..f1b8fdd7 100644 --- a/driving_environment_analyzer/launch/driving_environment_analyzer.launch.xml +++ b/driving_environment_analyzer/launch/driving_environment_analyzer.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/map/autoware_lanelet2_map_validator/src/common/cli.cpp b/map/autoware_lanelet2_map_validator/src/common/cli.cpp index b87941ad..6b130231 100644 --- a/map/autoware_lanelet2_map_validator/src/common/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/cli.cpp @@ -16,11 +16,7 @@ namespace po = boost::program_options; -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { MetaConfig parseCommandLine(int argc, const char * argv[]) @@ -102,6 +98,4 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) return config; } -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.cpp b/map/autoware_lanelet2_map_validator/src/common/validation.cpp index 35a8f99d..b3e33b8f 100644 --- a/map/autoware_lanelet2_map_validator/src/common/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.cpp @@ -39,11 +39,7 @@ // cSpell:words indegree Indegree -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { std::unique_ptr getProjector( @@ -416,6 +412,4 @@ void process_requirements(json json_data, const MetaConfig & validator_config) } } -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/cli.hpp index 600bb553..9e5d8f8c 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/cli.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/cli.hpp @@ -22,11 +22,7 @@ #include #include -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { struct MetaConfig { @@ -38,8 +34,6 @@ struct MetaConfig MetaConfig parseCommandLine(int argc, const char * argv[]); -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation #endif // LANELET2_MAP_VALIDATOR__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp index 775a9831..db93c2a4 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp @@ -21,11 +21,7 @@ #include #include -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { template void appendIssues(std::vector & to, std::vector && from) @@ -76,8 +72,6 @@ void checkPrimitivesType( } } -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation #endif // LANELET2_MAP_VALIDATOR__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp index 5b1d230d..fb90dffd 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp @@ -46,11 +46,7 @@ constexpr const char * utm = "utm"; } // namespace projector_names } // namespace -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { struct ValidatorInfo { @@ -90,8 +86,6 @@ lanelet::validation::ValidationConfig replace_validator( void process_requirements( json json_data, const lanelet::autoware::validation::MetaConfig & validator_config); -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation #endif // LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 94ebdd04..ff98c626 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -18,9 +18,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validation::MapValidator { @@ -33,8 +31,7 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati lanelet::validation::Issues checkMissingRegulatoryElementsForCrosswalks( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation // clang-format off #endif // LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ // NOLINT diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index a3c5ea13..81deea9e 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -18,9 +18,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validation::MapValidator { @@ -33,8 +31,7 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati private: lanelet::validation::Issues checkRegulatoryElementOfCrosswalks(const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation // clang-format off #endif // LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ // NOLINT diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 9a4c4f58..ed857b71 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -18,9 +18,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validation::MapValidator { @@ -33,8 +31,7 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio lanelet::validation::Issues checkMissingRegulatoryElementsForStopLines( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation // clang-format off #endif // LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ // NOLINT diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index 604f6c2b..16c85971 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -18,9 +18,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::validation::MapValidator { @@ -36,8 +34,7 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid lanelet::validation::Issues checkMissingRegulatoryElementsForTrafficLights( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation // clang-format off #endif // LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ // NOLINT diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index 6b31635d..07bbd840 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -20,9 +20,7 @@ #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::validation::MapValidator { @@ -40,8 +38,7 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid lanelet::validation::Issues checkRegulatoryElementOfTrafficLights( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation // clang-format off #endif // LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ // NOLINT diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index 165fdbc3..36716c14 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -21,9 +21,7 @@ #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -91,5 +89,4 @@ MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsF return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 70b36acc..da23b9ca 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -22,9 +22,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -125,5 +123,4 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 1fe24153..1f9aa2f1 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -25,9 +25,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -102,5 +100,4 @@ MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsFo return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp index 96eccf11..2ad34356 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp @@ -25,9 +25,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -92,5 +90,4 @@ MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElemen return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index ff9f4535..d163f3a1 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -21,9 +21,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -111,5 +109,4 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp index 42ae2769..c444a046 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp @@ -14,9 +14,7 @@ #include "validator_template.hpp" -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { namespace { @@ -32,5 +30,4 @@ lanelet::validation::Issues ValidatorTemplate::operator()(const lanelet::Lanelet return issues; } -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp index e541f4e0..1b4507ab 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp @@ -18,9 +18,7 @@ #include #include -namespace lanelet -{ -namespace validation +namespace lanelet::autoware::validation { class ValidatorTemplate : public lanelet::validation::MapValidator { @@ -32,7 +30,6 @@ class ValidatorTemplate : public lanelet::validation::MapValidator private: }; -} // namespace validation -} // namespace lanelet +} // namespace lanelet::autoware::validation #endif // VALIDATORS__VALIDATOR_TEMPLATE_HPP_ diff --git a/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp b/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp index 183936ab..9cee0749 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp @@ -27,11 +27,7 @@ using json = nlohmann::json; -namespace lanelet -{ -namespace autoware -{ -namespace validation +namespace lanelet::autoware::validation { class JsonProcessingTest : public ::testing::Test @@ -156,6 +152,4 @@ TEST_F(JsonProcessingTest, SummarizeValidatorResults) EXPECT_NE(output.find("Total of 1 errors were found"), std::string::npos); EXPECT_EQ(output.find("warnings were found"), std::string::npos); } -} // namespace validation -} // namespace autoware -} // namespace lanelet +} // namespace lanelet::autoware::validation diff --git a/planning/planning_debug_tools/README.md b/planning/planning_debug_tools/README.md index 48cc8838..d3e138ec 100644 --- a/planning/planning_debug_tools/README.md +++ b/planning/planning_debug_tools/README.md @@ -195,7 +195,7 @@ This script can overlay the perception results from the rosbag on the planning s ### How it works -Whenever the ego's position changes, a chronological `reproduce_sequence` queue is generated base on its position with a search radius (default to 2 m). +Whenever the ego's position changes, a chronological `reproduce_sequence` queue is generated based on its position with a search radius (default to 2 m). If the queue is empty, the nearest odom message in the rosbag is added to the queue. When publishing perception messages, the first element in the `reproduce_sequence` is popped and published. @@ -204,6 +204,18 @@ This design results in the following behavior: - When ego stops, the perception messages are published in chronological order until queue is empty. - When the ego moves, a perception message close to ego's position is published. +### Available Options + +- `-b`, `--bag`: Rosbag file path (required) +- `-d`, `--detected-object`: Publish detected objects +- `-t`, `--tracked-object`: Publish tracked objects +- `-r`, `--search-radius`: Set the search radius in meters (default: 1.5m). If set to 0, always publishes the nearest message +- `-c`, `--reproduce-cool-down`: Set the cool down time in seconds (default: 80.0s) +- `-p`, `--pub-route`: Initialize localization and publish a route based on poses from the rosbag +- `-n`, `--noise`: Apply perception noise to objects when publishing repeated messages (default: True) +- `-f`, `--rosbag-format`: Specify rosbag data format (default: "db3") +- `-v`, `--verbose`: Output debug data + ### How to use First, launch the planning simulator, and put the ego pose. @@ -223,8 +235,17 @@ ros2 run planning_debug_tools perception_reproducer.py -b Instead of publishing predicted objects, you can publish detected/tracked objects by designating `-d` or `-t`, respectively. -You can use `-r` option to set the search radius in meters for the perception messages. If it is set to 0, the reproducer always publishes the nearest perception message as how did the old perception_reproducer work. -`-c`(`--reproduce-cool-down`) option is to set the cool down time in seconds, aiming to prevent republishing recently published messages. +The `--pub-route` option enables automatic route generation based on the rosbag data. When enabled, the script: + +1. Extracts the initial and goal poses from the beginning and end of the rosbag file +2. Initializes the localization system with the initial pose +3. Generates and publishes a route to the goal pose + +Example usage with route publication: + +```bash +ros2 run planning_debug_tools perception_reproducer.py -b -p +``` ## Perception replayer diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index 3f63321b..8b32d0d0 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -24,6 +24,7 @@ import rclpy from utils import StopWatch from utils import create_empty_pointcloud +from utils import pub_route from utils import translate_objects_coordinate @@ -281,8 +282,8 @@ def add_perception_noise( if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-b", "--bag", help="rosbag", default=None) + parser = argparse.ArgumentParser(description="Perception Reproducer") + parser.add_argument("-b", "--bag", help="rosbag file path", required=True) parser.add_argument( "-n", "--noise", @@ -316,10 +317,23 @@ def add_perception_noise( type=float, default=80.0, ) - + parser.add_argument( + "-p", + "--pub-route", + help=( + "publish route created from the initial pose and goal pose retrieved from the beginning and end of the rosbag. " + "By default, route are not published." + ), + action="store_true", + ) args = parser.parse_args() - rclpy.init() + if not args.bag: + parser.error("The '--bag' argument is required.") + + if args.pub_route: + pub_route(args.bag) + node = PerceptionReproducer(args) try: diff --git a/planning/planning_debug_tools/scripts/perception_replayer/utils.py b/planning/planning_debug_tools/scripts/perception_replayer/utils.py index 34489f5b..f1f628e3 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/utils.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/utils.py @@ -16,14 +16,30 @@ import math import time +from typing import Tuple +from autoware_adapi_v1_msgs.srv import SetRoutePoints +from geometry_msgs.msg import Point +from geometry_msgs.msg import Pose +from geometry_msgs.msg import PoseWithCovariance +from geometry_msgs.msg import PoseWithCovarianceStamped from geometry_msgs.msg import Quaternion import numpy as np +import rclpy +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.node import Node +from rclpy.serialization import deserialize_message import rosbag2_py +from rosbag2_py import ConverterOptions +from rosbag2_py import SequentialReader +from rosbag2_py import StorageOptions +from rosidl_runtime_py.utilities import get_message from sensor_msgs.msg import PointCloud2 from sensor_msgs.msg import PointField +from std_msgs.msg import Header from tf_transformations import euler_from_quaternion from tf_transformations import quaternion_from_euler +from tier4_localization_msgs.srv import InitializeLocalization def get_starting_time(uri: str): @@ -131,6 +147,95 @@ def translate_objects_coordinate(ego_pose, log_ego_pose, objects_msg): object_pose.orientation = get_quaternion_from_yaw(log_object_yaw + log_ego_yaw - ego_yaw) +def create_reader(bag_dir: str) -> SequentialReader: + storage_options = StorageOptions(uri=bag_dir, storage_id="sqlite3") + converter_options = ConverterOptions( + input_serialization_format="cdr", output_serialization_format="cdr" + ) + reader = SequentialReader() + reader.open(storage_options, converter_options) + return reader + + +def is_close_pose(p0, p1, min_dist, max_dist) -> bool: + dist = np.linalg.norm([p0.x - p1.x, p0.y - p1.y, p0.z - p1.z]) + return dist < min_dist or dist > max_dist + + +def get_pose_from_bag(input_path: str, interval=(0.1, 10000.0)) -> Tuple[Pose, Pose]: + reader = create_reader(input_path) + type_map = { + topic_type.name: topic_type.type for topic_type in reader.get_all_topics_and_types() + } + pose_list = [] + is_first_pose = True + prev_trans = None + + while reader.has_next(): + topic, data, _ = reader.read_next() + if topic == "/tf": + msg_type = get_message(type_map[topic]) + msg = deserialize_message(data, msg_type) + for transform in msg.transforms: + if transform.child_frame_id != "base_link": + continue + trans = transform.transform.translation + rot = transform.transform.rotation + if is_first_pose: + is_first_pose = False + prev_trans = trans + elif is_close_pose(prev_trans, trans, interval[0], interval[1]): + continue + pose_list.append((trans, rot)) + prev_trans = trans + + if not pose_list: + raise ValueError("No valid poses found in the bag file.") + + initial_trans, initial_rot = pose_list[0] + goal_trans, goal_rot = pose_list[-1] + + initial_pose = Pose() + initial_pose.position = Point(x=initial_trans.x, y=initial_trans.y, z=initial_trans.z) + initial_pose.orientation = initial_rot + + goal_pose = Pose() + goal_pose.position = Point(x=goal_trans.x, y=goal_trans.y, z=goal_trans.z) + goal_pose.orientation = goal_rot + + return initial_pose, goal_pose + + +def pub_route(input_path: str): + rclpy.init() + + try: + first_pose, last_pose = get_pose_from_bag(input_path) + except Exception as e: + print(f"Error retrieving poses from bag: {e}") + return + + localization_client = LocalizationInitializer() + future_init = localization_client.send_initial_pose(first_pose) + rclpy.spin_until_future_complete(localization_client, future_init) + if future_init.result() is not None: + print("Successfully initialized localization.") + else: + print("Failed to initialize localization.") + + # temporarily add a sleep because sometimes the route is not generated correctly without it. + # Need to consider a proper solution. + time.sleep(2) + + route_client = RoutePointsClient() + future_route = route_client.send_request(last_pose) + rclpy.spin_until_future_complete(route_client, future_route) + if future_route.result() is not None: + print("Successfully set route points.") + else: + print("Failed to set route points.") + + class StopWatch: def __init__(self, verbose): # A dictionary to store the starting times @@ -155,3 +260,52 @@ def toc(self, name): # Reset the starting time for the name del self.start_times[name] + + +class LocalizationInitializer(Node): + def __init__(self): + super().__init__("localization_initializer") + self.callback_group = ReentrantCallbackGroup() + self.client = self.create_client( + InitializeLocalization, + "/localization/initialize", + callback_group=self.callback_group, + ) + while not self.client.wait_for_service(timeout_sec=1.0): + self.get_logger().info("Waiting for '/localization/initialize' service...") + + def create_initial_pose(self, pose: Pose) -> PoseWithCovarianceStamped: + pose_with_cov_stamped = PoseWithCovarianceStamped() + pose_with_cov_stamped.header.frame_id = "map" + pose_with_cov_stamped.header.stamp = self.get_clock().now().to_msg() + pose_with_cov = PoseWithCovariance() + pose_with_cov.pose = pose + covariance = np.identity(6) * 0.01 # Create a 6x6 identity matrix scaled by 0.01 + pose_with_cov.covariance = covariance.flatten().tolist() + pose_with_cov_stamped.pose = pose_with_cov + return pose_with_cov_stamped + + def send_initial_pose(self, pose: Pose): + request = InitializeLocalization.Request() + request.pose_with_covariance = [self.create_initial_pose(pose)] + request.method = 1 + self.get_logger().info("Sending initial pose request...") + return self.client.call_async(request) + + +class RoutePointsClient(Node): + def __init__(self): + super().__init__("route_points_client") + self.client = self.create_client(SetRoutePoints, "/api/routing/set_route_points") + while not self.client.wait_for_service(timeout_sec=1.0): + self.get_logger().info("Waiting for '/api/routing/set_route_points' service...") + + def send_request(self, goal_pose: Pose): + request = SetRoutePoints.Request() + request.header = Header() + request.header.stamp = self.get_clock().now().to_msg() + request.header.frame_id = "map" + request.goal = goal_pose + request.waypoints = [] + self.get_logger().info("Sending route points request...") + return self.client.call_async(request)