diff --git a/common/autoware_test_utils/config/sample_topic_snapshot.yaml b/common/autoware_test_utils/config/sample_topic_snapshot.yaml
new file mode 100644
index 0000000000000..854833bcb390d
--- /dev/null
+++ b/common/autoware_test_utils/config/sample_topic_snapshot.yaml
@@ -0,0 +1,25 @@
+format_version: 1
+
+num_frame: 1
+frame_interval: 0.1
+
+fields:
+ - name: self_odometry
+ type: Odometry # nav_msgs::msg::Odometry
+ topic: /localization/kinematic_state
+
+ - name: self_acceleration
+ type: AccelWithCovarianceStamped # geometry_msgs::msg::AccelWithCovarianceStamped
+ topic: /localization/acceleration
+
+ - name: operation_mode
+ type: OperationModeState # autoware_adapi_v1_msgs::msg::OperationModeState
+ topic: /system/operation_mode/state
+
+ - name: route
+ type: LaneletRoute # autoware_planning_msgs::msg::LaneletRoute
+ topic: /planning/mission_planning/route
+
+ - name: traffic_signal
+ type: TrafficLightGroupArray # autoware_perception_msgs::msg::TrafficLightGroupArray
+ topic: /perception/traffic_light_recognition/traffic_signals
diff --git a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml
index 73cedd98647b7..07efdcb742cf0 100644
--- a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml
+++ b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml
@@ -13,4 +13,9 @@
+
+
+
+
+
diff --git a/common/autoware_test_utils/src/topic_snapshot_saver.cpp b/common/autoware_test_utils/src/topic_snapshot_saver.cpp
index 846bc4f4a4cbd..46bd657cd470e 100644
--- a/common/autoware_test_utils/src/topic_snapshot_saver.cpp
+++ b/common/autoware_test_utils/src/topic_snapshot_saver.cpp
@@ -13,6 +13,7 @@
// limitations under the License.
#include
+#include
#include
#include
@@ -27,6 +28,7 @@
#include
#include
+#include
#include
#include
#include
@@ -65,6 +67,8 @@ std::optional get_topic_index(const std::string & name)
return std::nullopt;
}
+std::mutex g_mutex;
+
template
typename rclcpp::SubscriptionBase::SharedPtr create_subscriber(
const std::string & topic_name, rclcpp::Node & node, Callback && callback)
@@ -77,20 +81,35 @@ template
class CallbackHandler
{
public:
- CallbackHandler(std::mutex & m, MessageType & buffer) : mutex_(m), buffer_(buffer) {}
+ CallbackHandler(MessageType & buffer) : buffer_(buffer) {}
- // nav_msgs::msg::Odometry_>::SharedPtr
void on_callback(const typename Message::SharedPtr msg)
{
- std::lock_guard guard(mutex_);
- buffer_ = *msg;
+ std::lock_guard guard(g_mutex);
+ if (msg) {
+ buffer_ = *msg;
+ }
}
private:
- std::mutex & mutex_;
MessageType & buffer_;
};
+namespace detail
+{
+template
+struct CallbackHandlerType;
+
+template
+struct CallbackHandlerType>
+{
+ using type = std::variant...>;
+};
+} // namespace detail
+
+template
+using CallbackHandlerType = typename detail::CallbackHandlerType::type;
+
std::optional resolve_pkg_share_uri(const std::string & uri_path)
{
std::smatch match;
@@ -111,12 +130,14 @@ class TopicSnapShotSaver
const std::string & map_path, const std::string & config_path, rclcpp::Node & node)
: map_path_(map_path), config_path_(config_path)
{
+ std::lock_guard guard(g_mutex);
+
server_ = node.create_service(
"/autoware_test_utils/topic_snapshot_saver",
std::bind(
&TopicSnapShotSaver::on_service, this, std::placeholders::_1, std::placeholders::_2));
- // get map hash
+ // get map version
// setup subscribers and callbacks
const auto config = YAML::LoadFile(config_path);
for (const auto field : config["fields"]) {
@@ -127,33 +148,106 @@ class TopicSnapShotSaver
}
const auto type_index = type_index_opt.value();
const auto topic = field["topic"].as();
- if (type_index == 0) {
+ field_2_topic_type_[name] = type_index;
+
+ /*
+ if (0 == type_index) {
CallbackHandler> handler(
- mutex_, message_buffer_.at(0));
- const auto sub = create_subscriber<0>(
+ std::ref(mutex_), std::ref(message_buffer_.at(0)));
+ handlers_.emplace_back(handler);
+ auto & handler_ref =
+ std::get>>(
+ handlers_.back());
+ subscribers_[0] = create_subscriber<0>(
topic, node,
std::bind(
- &CallbackHandler>::on_callback, &handler,
+ &CallbackHandler>::on_callback, &handler_ref,
std::placeholders::_1));
}
- }
+ */
+
+ /**
+ * NOTE: for a specific topic-type, only one topic-name is allowed
+ *
+ * `message_buffer_` holds buffer for each topic-type for the lifetime duration of this class
+ *
+ * `subscribers_` holds a subscriber for each topic-type for the lifetime duration of this
+ * class
+ *
+ * `handlers_` holds a handler for each topic-type for the lifetime duration of this
+ * class
+ *
+ */
+
+#define REGISTER_CALLBACK(arg) \
+ if (arg == type_index) { \
+ CallbackHandler> handler( \
+ std::ref(message_buffer_.at(arg))); \
+ handlers_.emplace_back(handler); \
+ auto & handler_ref = \
+ std::get>>( \
+ handlers_.back()); \
+ subscribers_[arg] = create_subscriber( \
+ topic, node, \
+ std::bind( \
+ &CallbackHandler>::on_callback, &handler_ref, \
+ std::placeholders::_1)); \
}
- void on_callback([[maybe_unused]] const nav_msgs::msg::Odometry::SharedPtr msg) { return; }
+ REGISTER_CALLBACK(0);
+ REGISTER_CALLBACK(1);
+ REGISTER_CALLBACK(2);
+ REGISTER_CALLBACK(3);
+ REGISTER_CALLBACK(4);
+ REGISTER_CALLBACK(5);
+ }
+ }
+private:
const std::string map_path_;
const std::string config_path_;
rclcpp::Service::SharedPtr server_;
- std::unordered_map subscribers_;
+ std::unordered_map subscribers_;
+ std::vector> handlers_;
std::array> message_buffer_;
- std::mutex mutex_;
-
+ std::unordered_map field_2_topic_type_;
void on_service(
[[maybe_unused]] const std::shared_ptr req,
[[maybe_unused]] std::shared_ptr res)
{
+ std::lock_guard guard(g_mutex);
+
+ YAML::Node yaml;
+
+ yaml["format_version"] = 1;
+
+ for (const auto & [field, type_index] : field_2_topic_type_) {
+ if (0 == type_index) {
+ const auto & msg = std::get>(
+ message_buffer_.at(type_index));
+ yaml[field] = to_yaml(msg); // NOTE: ADL works fine!
+ }
+ }
+
+ const std::string desc = std::string(R"(#
+# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver
+# format1:
+#
+# format_version:
+# fields(this is array)
+# - name:
+# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray}
+# topic:
+#
+)");
+
+ std::ofstream ofs("topic_snapshot.yaml");
+ ofs << desc;
+ ofs << yaml;
+
+ std::cout << "saved planner_data" << std::endl;
}
};
@@ -165,6 +259,7 @@ class TopicSnapShotSaverFrontEnd : public rclcpp::Node
const auto map_path_uri = declare_parameter("map_path", "none");
const auto config_path_uri = declare_parameter("config_path", "none");
if (map_path_uri == "none" || config_path_uri == "none") {
+ RCLCPP_ERROR(get_logger(), "map_path_uri and/or config_path_uri are not provided");
return;
}
const auto map_path = resolve_pkg_share_uri(map_path_uri);
@@ -192,4 +287,14 @@ class TopicSnapShotSaverFrontEnd : public rclcpp::Node
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
+
+ rclcpp::executors::SingleThreadedExecutor exec;
+
+ auto node = std::make_shared();
+
+ exec.add_node(node);
+
+ exec.spin();
+
+ rclcpp::shutdown();
}