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.
PoseToTF2Node.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2020-2022 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 <tf2_ros/transform_broadcaster.h>
22#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23
24namespace pose_to_tf
25{
26
32 class PoseToTfNode : public carma_ros2_utils::CarmaLifecycleNode
33 {
34
35 private:
36 // Subscribers
37 carma_ros2_utils::SubPtr<geometry_msgs::msg::Pose> pose_sub;
38 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> pose_stamped_sub;
39 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseWithCovariance> pose_with_cov_sub;
40 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseWithCovarianceStamped> pose_with_cov_stamped_sub;
41
42 //PoseToTF2 class object
43 std::shared_ptr <PoseToTF2> pose_to_tf_worker_;
44
45 // Node configuration
47
48 public:
49
53 explicit PoseToTfNode(const rclcpp::NodeOptions &);
54
56 // Overrides
58 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
59
60 };
61
62} // pose_to_tf
The class is responsible for processing pose to tf conversion.
std::shared_ptr< PoseToTF2 > pose_to_tf_worker_
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovarianceStamped > pose_with_cov_stamped_sub
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseWithCovariance > pose_with_cov_sub
PoseToTfNode(const rclcpp::NodeOptions &)
PoseToTfNode constructor.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_stamped_sub
carma_ros2_utils::SubPtr< geometry_msgs::msg::Pose > pose_sub
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
Stuct containing the frame configuration values for pose_to_tf.