|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "trajectory_repeater.hpp" |
| 16 | + |
| 17 | +namespace trajectory_repeater |
| 18 | +{ |
| 19 | + |
| 20 | +TrajectoryRepeater::TrajectoryRepeater(const rclcpp::NodeOptions & node_options) |
| 21 | +: Node("trajectory_repeater", node_options) |
| 22 | +{ |
| 23 | + // Parameter |
| 24 | + |
| 25 | + // Subscriber |
| 26 | + sub_trajectory_ = create_subscription<autoware_auto_planning_msgs::msg::Trajectory>( |
| 27 | + "~/input/trajectory", 10, std::bind(&TrajectoryRepeater::onTrajectory, this, std::placeholders::_1)); |
| 28 | + |
| 29 | + // Publisher |
| 30 | + pub_trajectory_ = create_publisher<autoware_auto_planning_msgs::msg::Trajectory>("~/output/trajectory", 10); |
| 31 | + |
| 32 | + // Service |
| 33 | + |
| 34 | + // Client |
| 35 | + |
| 36 | + // Timer |
| 37 | + using namespace std::literals::chrono_literals; |
| 38 | + timer_ = rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&TrajectoryRepeater::onTimer, this)); |
| 39 | + |
| 40 | + // State |
| 41 | + |
| 42 | + // Diagnostics |
| 43 | + |
| 44 | +} |
| 45 | + |
| 46 | +void TrajectoryRepeater::onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg) |
| 47 | +{ |
| 48 | + last_trajectory_ = msg; |
| 49 | +} |
| 50 | + |
| 51 | +void TrajectoryRepeater::onTimer() |
| 52 | +{ |
| 53 | + if (!last_trajectory_) { |
| 54 | + RCLCPP_DEBUG(get_logger(), "No trajectory received"); |
| 55 | + return; |
| 56 | + } |
| 57 | + |
| 58 | + pub_trajectory_->publish(*last_trajectory_); |
| 59 | +} |
| 60 | + |
| 61 | +} // namespace trajectory_repeater |
| 62 | + |
| 63 | +#include <rclcpp_components/register_node_macro.hpp> |
| 64 | +RCLCPP_COMPONENTS_REGISTER_NODE(trajectory_repeater::TrajectoryRepeater) |
0 commit comments