Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
frame_transformer_node.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2021 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
17
18#include <rclcpp/rclcpp.hpp>
19#include <functional>
20#include <std_msgs/msg/string.hpp>
21#include <std_srvs/srv/empty.hpp>
22#include <gtest/gtest_prod.h>
23
24#include <carma_ros2_utils/carma_lifecycle_node.hpp>
28
29namespace frame_transformer
30{
31
36 class Node : public carma_ros2_utils::CarmaLifecycleNode
37 {
38
39 private:
40
43
45 std::unique_ptr<TransformerBase> transformer_;
46
48 std::shared_ptr<tf2_ros::Buffer> buffer_;
49
51 std::shared_ptr<tf2_ros::TransformListener> listener_;
52
53 public:
57 explicit Node(const rclcpp::NodeOptions &);
58
59
67 std::unique_ptr<TransformerBase> build_transformer();
68
70 // Overrides
72 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
73
74 carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &);
75
76 // Unit Test Accessors
77 FRIEND_TEST(frame_transformer_test, transform_test);
78 FRIEND_TEST(frame_transformer_test, point_cloud_transform_test);
79
80 };
81
82} // frame_transformer
Node which subcribes to and input topic, transforms the data into a new frame and republishes it onto...
FRIEND_TEST(frame_transformer_test, transform_test)
std::unique_ptr< TransformerBase > build_transformer()
Factory method which returns an initialized pointer to a TransformerBase.
FRIEND_TEST(frame_transformer_test, point_cloud_transform_test)
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &)
std::shared_ptr< tf2_ros::Buffer > buffer_
tf2 Buffer to store transforms broadcast on the system
Config config_
Node configuration.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
std::unique_ptr< TransformerBase > transformer_
Pointer to a transformer which will setup its own pub/subs to perform the transformation
std::shared_ptr< tf2_ros::TransformListener > listener_
tf2 Listener to subscribe to system transform broadcasts
Node(const rclcpp::NodeOptions &)
Node constructor.
Stuct containing the algorithm configuration values for frame_transformer.