|
| 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 | +#ifndef AUTOWARE_JOY_CONTROLLER__AUTOWARE_JOY_CONTROLLER_HPP_ |
| 16 | +#define AUTOWARE_JOY_CONTROLLER__AUTOWARE_JOY_CONTROLLER_HPP_ |
| 17 | + |
| 18 | +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" |
| 19 | + |
| 20 | +#include <rclcpp/rclcpp.hpp> |
| 21 | + |
| 22 | +#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp> |
| 23 | +#include <autoware_auto_vehicle_msgs/msg/engage.hpp> |
| 24 | +#include <autoware_control_msgs/msg/gate_mode.hpp> |
| 25 | +#include <autoware_external_api_msgs/msg/control_command_stamped.hpp> |
| 26 | +#include <autoware_external_api_msgs/msg/gear_shift_stamped.hpp> |
| 27 | +#include <autoware_external_api_msgs/msg/heartbeat.hpp> |
| 28 | +#include <autoware_external_api_msgs/msg/turn_signal_stamped.hpp> |
| 29 | +#include <autoware_external_api_msgs/srv/engage.hpp> |
| 30 | +#include <autoware_external_api_msgs/srv/set_emergency.hpp> |
| 31 | +#include <geometry_msgs/msg/twist_stamped.hpp> |
| 32 | +#include <nav_msgs/msg/odometry.hpp> |
| 33 | +#include <sensor_msgs/msg/joy.hpp> |
| 34 | + |
| 35 | +#include <algorithm> |
| 36 | +#include <memory> |
| 37 | +#include <string> |
| 38 | + |
| 39 | +namespace autoware_joy_controller |
| 40 | +{ |
| 41 | +using GearShiftType = autoware_external_api_msgs::msg::GearShift::_data_type; |
| 42 | +using TurnSignalType = autoware_external_api_msgs::msg::TurnSignal::_data_type; |
| 43 | +using GateModeType = autoware_control_msgs::msg::GateMode::_data_type; |
| 44 | + |
| 45 | +class AutowareJoyControllerNode : public rclcpp::Node |
| 46 | +{ |
| 47 | +public: |
| 48 | + explicit AutowareJoyControllerNode(const rclcpp::NodeOptions & node_options); |
| 49 | + |
| 50 | +private: |
| 51 | + // Parameter |
| 52 | + std::string joy_type_; |
| 53 | + double update_rate_; |
| 54 | + double accel_ratio_; |
| 55 | + double brake_ratio_; |
| 56 | + double steer_ratio_; |
| 57 | + double steering_angle_velocity_; |
| 58 | + double accel_sensitivity_; |
| 59 | + double brake_sensitivity_; |
| 60 | + |
| 61 | + // ControlCommand Parameter |
| 62 | + double velocity_gain_; |
| 63 | + double max_forward_velocity_; |
| 64 | + double max_backward_velocity_; |
| 65 | + double backward_accel_ratio_; |
| 66 | + |
| 67 | + // CallbackGroups |
| 68 | + rclcpp::CallbackGroup::SharedPtr callback_group_subscribers_; |
| 69 | + rclcpp::CallbackGroup::SharedPtr callback_group_services_; |
| 70 | + |
| 71 | + // Subscriber |
| 72 | + rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr sub_joy_; |
| 73 | + rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_; |
| 74 | + |
| 75 | + rclcpp::Time last_joy_received_time_; |
| 76 | + std::shared_ptr<const JoyConverterBase> joy_; |
| 77 | + geometry_msgs::msg::TwistStamped::ConstSharedPtr twist_; |
| 78 | + |
| 79 | + void onJoy(const sensor_msgs::msg::Joy::ConstSharedPtr msg); |
| 80 | + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); |
| 81 | + |
| 82 | + // Publisher |
| 83 | + rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr |
| 84 | + pub_control_command_; |
| 85 | + rclcpp::Publisher<autoware_external_api_msgs::msg::ControlCommandStamped>::SharedPtr |
| 86 | + pub_external_control_command_; |
| 87 | + rclcpp::Publisher<autoware_external_api_msgs::msg::GearShiftStamped>::SharedPtr pub_shift_; |
| 88 | + rclcpp::Publisher<autoware_external_api_msgs::msg::TurnSignalStamped>::SharedPtr pub_turn_signal_; |
| 89 | + rclcpp::Publisher<autoware_external_api_msgs::msg::Heartbeat>::SharedPtr pub_heartbeat_; |
| 90 | + rclcpp::Publisher<autoware_control_msgs::msg::GateMode>::SharedPtr pub_gate_mode_; |
| 91 | + rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::Engage>::SharedPtr pub_vehicle_engage_; |
| 92 | + |
| 93 | + void publishControlCommand(); |
| 94 | + void publishExternalControlCommand(); |
| 95 | + void publishShift(); |
| 96 | + void publishTurnSignal(); |
| 97 | + void publishGateMode(); |
| 98 | + void publishHeartbeat(); |
| 99 | + void publishAutowareEngage(); |
| 100 | + void publishVehicleEngage(); |
| 101 | + void sendEmergencyRequest(bool emergency); |
| 102 | + |
| 103 | + // Service Client |
| 104 | + rclcpp::Client<autoware_external_api_msgs::srv::SetEmergency>::SharedPtr client_emergency_stop_; |
| 105 | + rclcpp::Client<autoware_external_api_msgs::srv::Engage>::SharedPtr client_autoware_engage_; |
| 106 | + |
| 107 | + // Previous State |
| 108 | + autoware_auto_control_msgs::msg::AckermannControlCommand prev_control_command_; |
| 109 | + autoware_external_api_msgs::msg::ControlCommand prev_external_control_command_; |
| 110 | + GearShiftType prev_shift_ = autoware_external_api_msgs::msg::GearShift::NONE; |
| 111 | + TurnSignalType prev_turn_signal_ = autoware_external_api_msgs::msg::TurnSignal::NONE; |
| 112 | + GateModeType prev_gate_mode_ = autoware_control_msgs::msg::GateMode::AUTO; |
| 113 | + |
| 114 | + // Timer |
| 115 | + rclcpp::TimerBase::SharedPtr timer_; |
| 116 | + void initTimer(double period_s); |
| 117 | + |
| 118 | + bool isDataReady(); |
| 119 | + void onTimer(); |
| 120 | +}; |
| 121 | +} // namespace autoware_joy_controller |
| 122 | + |
| 123 | +#endif // AUTOWARE_JOY_CONTROLLER__AUTOWARE_JOY_CONTROLLER_HPP_ |
0 commit comments