|
| 1 | +// Copyright 2020 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 "shift_decider/shift_decider.hpp" |
| 16 | + |
| 17 | +#include <rclcpp/timer.hpp> |
| 18 | + |
| 19 | +#include <cstddef> |
| 20 | +#include <functional> |
| 21 | +#include <memory> |
| 22 | +#include <utility> |
| 23 | + |
| 24 | +ShiftDecider::ShiftDecider(const rclcpp::NodeOptions & node_options) |
| 25 | +: Node("shift_decider", node_options) |
| 26 | +{ |
| 27 | + using std::placeholders::_1; |
| 28 | + |
| 29 | + static constexpr std::size_t queue_size = 1; |
| 30 | + rclcpp::QoS durable_qos(queue_size); |
| 31 | + durable_qos.transient_local(); |
| 32 | + |
| 33 | + pub_shift_cmd_ = |
| 34 | + create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>("output/gear_cmd", durable_qos); |
| 35 | + sub_control_cmd_ = create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>( |
| 36 | + "input/control_cmd", queue_size, std::bind(&ShiftDecider::onControlCmd, this, _1)); |
| 37 | + |
| 38 | + initTimer(0.1); |
| 39 | +} |
| 40 | + |
| 41 | +void ShiftDecider::onControlCmd( |
| 42 | + autoware_auto_control_msgs::msg::AckermannControlCommand::SharedPtr msg) |
| 43 | +{ |
| 44 | + control_cmd_ = msg; |
| 45 | +} |
| 46 | + |
| 47 | +void ShiftDecider::onTimer() |
| 48 | +{ |
| 49 | + if (!control_cmd_) { |
| 50 | + return; |
| 51 | + } |
| 52 | + |
| 53 | + updateCurrentShiftCmd(); |
| 54 | + pub_shift_cmd_->publish(shift_cmd_); |
| 55 | +} |
| 56 | + |
| 57 | +void ShiftDecider::updateCurrentShiftCmd() |
| 58 | +{ |
| 59 | + using autoware_auto_vehicle_msgs::msg::GearCommand; |
| 60 | + |
| 61 | + shift_cmd_.stamp = now(); |
| 62 | + static constexpr double vel_threshold = 0.01; // to prevent chattering |
| 63 | + if (control_cmd_->longitudinal.speed > vel_threshold) { |
| 64 | + shift_cmd_.command = GearCommand::DRIVE; |
| 65 | + } else if (control_cmd_->longitudinal.speed < -vel_threshold) { |
| 66 | + shift_cmd_.command = GearCommand::REVERSE; |
| 67 | + } |
| 68 | +} |
| 69 | + |
| 70 | +void ShiftDecider::initTimer(double period_s) |
| 71 | +{ |
| 72 | + auto timer_callback = std::bind(&ShiftDecider::onTimer, this); |
| 73 | + const auto period_ns = |
| 74 | + std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<double>(period_s)); |
| 75 | + timer_ = std::make_shared<rclcpp::GenericTimer<decltype(timer_callback)>>( |
| 76 | + this->get_clock(), period_ns, std::move(timer_callback), |
| 77 | + this->get_node_base_interface()->get_context()); |
| 78 | + this->get_node_timers_interface()->add_timer(timer_, nullptr); |
| 79 | +} |
| 80 | + |
| 81 | +#include <rclcpp_components/register_node_macro.hpp> |
| 82 | +RCLCPP_COMPONENTS_REGISTER_NODE(ShiftDecider) |
0 commit comments