|
| 1 | +// Copyright (c) 2024, OUXT-Polaris |
| 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 <algorithm> |
| 16 | +#include <iostream> |
| 17 | +#include <memory> |
| 18 | +#include <optional> |
| 19 | +#include <string> |
| 20 | +#include <vector> |
| 21 | + |
| 22 | +#include "geometry_msgs/msg/pose_stamped.hpp" |
| 23 | +#include "hermite_path_msgs/msg/planner_status.hpp" |
| 24 | +#include "rclcpp/rclcpp.hpp" |
| 25 | +#include "robotx_behavior_msgs/msg/task_object.hpp" |
| 26 | +#include "robotx_behavior_tree/action_node.hpp" |
| 27 | + |
| 28 | +namespace robotx_behavior_tree |
| 29 | +{ |
| 30 | +class MoveToFrontPoseOfObject : public ActionROS2Node |
| 31 | +{ |
| 32 | +public: |
| 33 | + MoveToFrontPoseOfObject(const std::string & name, const BT::NodeConfiguration & config) |
| 34 | + : ActionROS2Node(name, config) |
| 35 | + { |
| 36 | + declare_parameter("goal_tolerance", 1.0); |
| 37 | + get_parameter("goal_tolerance", goal_tolerance_); |
| 38 | + goal_pub_front_pose_of_object_ = |
| 39 | + this->create_publisher<geometry_msgs::msg::PoseStamped>("/move_base_simple/goal", 1); |
| 40 | + } |
| 41 | + static BT::PortsList providedPorts() |
| 42 | + { |
| 43 | + return appendPorts( |
| 44 | + ActionROS2Node::providedPorts(), {BT::InputPort<std::string>("object_type")}); |
| 45 | + } |
| 46 | + |
| 47 | +private: |
| 48 | + rclcpp::TimerBase::SharedPtr update_position_timer_; |
| 49 | + float distance_; |
| 50 | + double goal_tolerance_; |
| 51 | + geometry_msgs::msg::PoseStamped goal_; |
| 52 | + rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr goal_pub_front_pose_of_object_; |
| 53 | + std::vector<robotx_behavior_msgs::msg::TaskObject> target_objects_array_; |
| 54 | + |
| 55 | + enum class Buoy : short { |
| 56 | + BUOY_RED = robotx_behavior_msgs::msg::TaskObject::BUOY_RED, |
| 57 | + BUOY_GREEN = robotx_behavior_msgs::msg::TaskObject::BUOY_GREEN, |
| 58 | + BUOY_WHITE = robotx_behavior_msgs::msg::TaskObject::BUOY_WHITE, |
| 59 | + BUOY_BLACK = robotx_behavior_msgs::msg::TaskObject::BUOY_BLACK |
| 60 | + }; |
| 61 | + enum class Status : short { |
| 62 | + WAITING_FOR_GOAL = hermite_path_msgs::msg::PlannerStatus::WAITING_FOR_GOAL, |
| 63 | + MOVING_TO_GOAL = hermite_path_msgs::msg::PlannerStatus::MOVING_TO_GOAL, |
| 64 | + AVOIDING = hermite_path_msgs::msg::PlannerStatus::MOVING_TO_GOAL |
| 65 | + }; |
| 66 | + |
| 67 | +protected: |
| 68 | + BT::NodeStatus onStart() override |
| 69 | + { |
| 70 | + const auto status_planner = getPlannerStatus(); |
| 71 | + const auto task_objects_array = getTaskObjects(); |
| 72 | + if (task_objects_array) { |
| 73 | + RCLCPP_INFO(get_logger(), "get task_objects"); |
| 74 | + return BT::NodeStatus::RUNNING; |
| 75 | + } else { |
| 76 | + return BT::NodeStatus::FAILURE; |
| 77 | + } |
| 78 | + } |
| 79 | + |
| 80 | + BT::NodeStatus onRunning() override |
| 81 | + { |
| 82 | + const auto status_planner = getPlannerStatus(); |
| 83 | + const auto pose = getCurrentPose(); |
| 84 | + const auto task_objects_array = getTaskObjects(); |
| 85 | + |
| 86 | + auto object_type = this->getInput<std::string>("object_type"); |
| 87 | + |
| 88 | + if (task_objects_array) { |
| 89 | + if (object_type.value() == "red_bouy") { |
| 90 | + target_objects_array_ = |
| 91 | + filter(task_objects_array.value(), static_cast<short>(Buoy::BUOY_RED)); |
| 92 | + } else if (object_type.value() == "green_bouy") { |
| 93 | + target_objects_array_ = |
| 94 | + filter(task_objects_array.value(), static_cast<short>(Buoy::BUOY_GREEN)); |
| 95 | + } else if (object_type.value() == "white_bouy") { |
| 96 | + target_objects_array_ = |
| 97 | + filter(task_objects_array.value(), static_cast<short>(Buoy::BUOY_WHITE)); |
| 98 | + } else if (object_type.value() == "black_bouy") { |
| 99 | + target_objects_array_ = |
| 100 | + filter(task_objects_array.value(), static_cast<short>(Buoy::BUOY_BLACK)); |
| 101 | + } else { |
| 102 | + return BT::NodeStatus::FAILURE; |
| 103 | + } |
| 104 | + } |
| 105 | + |
| 106 | + sortBy2DDistance(target_objects_array_, pose.value()->pose.position); |
| 107 | + if (target_objects_array_.empty()) { |
| 108 | + return BT::NodeStatus::FAILURE; |
| 109 | + } |
| 110 | + |
| 111 | + const auto front_pose = getFrontPoseOfObject(target_objects_array_[0], 7.0); |
| 112 | + get_parameter("goal_tolerance", goal_tolerance_); |
| 113 | + goal_.header.frame_id = "map"; |
| 114 | + if (front_pose) { |
| 115 | + goal_.pose.position.x = front_pose.value().position.x; |
| 116 | + goal_.pose.position.y = front_pose.value().position.y; |
| 117 | + goal_.pose.position.z = front_pose.value().position.z; |
| 118 | + goal_.pose.orientation.w = front_pose.value().orientation.w; |
| 119 | + goal_.pose.orientation.x = front_pose.value().orientation.x; |
| 120 | + goal_.pose.orientation.y = front_pose.value().orientation.y; |
| 121 | + goal_.pose.orientation.z = front_pose.value().orientation.z; |
| 122 | + } |
| 123 | + goal_.header.stamp = get_clock()->now(); |
| 124 | + if (status_planner.value()->status == static_cast<short>(Status::WAITING_FOR_GOAL)) { |
| 125 | + goal_pub_front_pose_of_object_->publish(goal_); |
| 126 | + } |
| 127 | + distance_ = getDistance(pose.value()->pose.position, goal_.pose.position); |
| 128 | + |
| 129 | + if (distance_ < goal_tolerance_) { |
| 130 | + RCLCPP_INFO(get_logger(), "Throgh Goal : SUCCESS"); |
| 131 | + return BT::NodeStatus::SUCCESS; |
| 132 | + } |
| 133 | + |
| 134 | + return BT::NodeStatus::RUNNING; |
| 135 | + } |
| 136 | +}; |
| 137 | +} // namespace robotx_behavior_tree |
| 138 | + |
| 139 | +#include "behavior_tree_action_builder/register_nodes.hpp" // NOLINT |
| 140 | + |
| 141 | +REGISTER_NODES(robotx_behavior_tree, MoveToFrontPoseOfObject) |
0 commit comments