Skip to content

Commit 0903ab6

Browse files
Merge pull request #94 from OUXT-Polaris/feature/go_object_waypoint
オブジェクトの前に移動する関数を追加
2 parents 739c925 + f75c608 commit 0903ab6

File tree

7 files changed

+248
-7
lines changed

7 files changed

+248
-7
lines changed

robotx_behavior_msgs/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
3131
)
3232

3333
if(BUILD_TESTING)
34-
find_package(ament_lint_auto REQUIRED)
35-
ament_lint_auto_find_test_dependencies()
34+
find_package(ament_lint_auto REQUIRED)
35+
ament_lint_auto_find_test_dependencies()
3636
endif()
3737

3838
ament_package()

robotx_behavior_tree/CMakeLists.txt

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,7 @@ endif()
1414
find_package(ament_cmake_auto REQUIRED)
1515
ament_auto_find_build_dependencies()
1616

17-
#include_directories(include ${CMAKE_CURRENT_BINARY_DIR})
18-
19-
#set(library_name ${PROJECT_NAME})
17+
include_directories(include ${EIGEN3_INCLUDE_DIR})
2018

2119
ament_auto_add_library(example_action SHARED plugins/action/example_action.cpp)
2220
target_compile_definitions(example_action PRIVATE BT_PLUGIN_EXPORT)
@@ -36,6 +34,9 @@ target_compile_definitions(set_turn_action PRIVATE BT_PLUGIN_EXPORT)
3634
ament_auto_add_library(move_to_gate_action SHARED plugins/action/move_to_gate_action.cpp)
3735
target_compile_definitions(move_to_gate_action PRIVATE BT_PLUGIN_EXPORT)
3836

37+
ament_auto_add_library(move_to_front_pose_of_object SHARED plugins/action/move_to_front_pose_of_object.cpp)
38+
target_compile_definitions(move_to_front_pose_of_object PRIVATE BT_PLUGIN_EXPORT)
39+
3940
ament_auto_add_library(to_marker SHARED src/to_marker.cpp)
4041

4142
install(TARGETS
@@ -50,6 +51,8 @@ install(DIRECTORY models DESTINATION share/${PROJECT_NAME})
5051
if(BUILD_TESTING)
5152
find_package(ament_lint_auto REQUIRED)
5253
ament_lint_auto_find_test_dependencies()
54+
find_package(ament_cmake_gtest REQUIRED)
55+
ament_auto_add_gtest(test_action_node test/src/test_action_node.cpp)
5356
endif()
5457

5558
ament_auto_package()

robotx_behavior_tree/include/robotx_behavior_tree/action_node.hpp

Lines changed: 27 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,6 @@ class ActionROS2Node : public BT::StatefulActionNode, public rclcpp::Node
139139
DEFINE_GET_INPUT(
140140
TaskObjects, robotx_behavior_msgs::msg::TaskObjectsArrayStamped::SharedPtr, "task_objects");
141141
#undef DEFINE_GET_INPUT
142-
143142
template <typename T1, typename T2>
144143
double getDistance(const T1 & p1, const T2 & p2) const
145144
{
@@ -202,7 +201,6 @@ class ActionROS2Node : public BT::StatefulActionNode, public rclcpp::Node
202201
p.z = task_object.z[0];
203202
return p;
204203
}
205-
206204
geometry_msgs::msg::Point2D getPoint2D(
207205
const robotx_behavior_msgs::msg::TaskObject & task_object) const
208206
{
@@ -307,6 +305,33 @@ class ActionROS2Node : public BT::StatefulActionNode, public rclcpp::Node
307305
p.orientation = quaternion_operation::convertEulerAngleToQuaternion(goal_rpy);
308306
return p;
309307
}
308+
309+
std::optional<geometry_msgs::msg::Pose> getFrontPoseOfObject(
310+
const robotx_behavior_msgs::msg::TaskObject & obj, const double distance = 7.0) const
311+
{
312+
const auto current_pose = getCurrentPose();
313+
if (!current_pose) {
314+
return std::nullopt;
315+
}
316+
double delta_x = obj.x - current_pose.value()->pose.position.x;
317+
double delta_y = obj.y - current_pose.value()->pose.position.y;
318+
const double minimum_delta = 0.1;
319+
if (abs(delta_x) < minimum_delta) {
320+
delta_x = minimum_delta;
321+
}
322+
if (abs(delta_y) < minimum_delta) {
323+
delta_y = minimum_delta;
324+
}
325+
double theta = std::atan2(delta_y, delta_x);
326+
geometry_msgs::msg::Pose p;
327+
p.position.x = obj.x - distance * std::cos(theta);
328+
p.position.y = obj.y - distance * std::sin(theta);
329+
p.position.z = 0.0;
330+
geometry_msgs::msg::Vector3 goal_rpy;
331+
goal_rpy.z = theta;
332+
p.orientation = quaternion_operation::convertEulerAngleToQuaternion(goal_rpy);
333+
return p;
334+
}
310335
};
311336
} // namespace robotx_behavior_tree
312337

Lines changed: 141 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,141 @@
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)
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
// Copyright (c) 2023 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+
/**
16+
* @file test_action_node.cpp
17+
* @author Kento Hirogaki hkt8g2r6kin@gmail.com
18+
* @brief test code for Action Node
19+
* @version 0.1
20+
* @date 2023-10-17
21+
*
22+
* @copyright Copyright (c) 2023
23+
*
24+
*/
25+
#include <gtest/gtest.h>
26+
27+
#include <robotx_behavior_tree/action_node.hpp>
28+
29+
TEST(TestSuite, testCase1)
30+
{
31+
robotx_behavior_msgs::msg::TaskObject object;
32+
// robotx_behavior_tree::ActionROS2Node *testtest();
33+
object.x = 0;
34+
object.y = 0;
35+
36+
// object->x = 0;
37+
// object->y = 0;
38+
// robotx_behavior_tree::ActionROS2Node::getFrontPoseForWaypoint(object, 2.0);
39+
40+
// robotx_behavior_tree::getFrontPoseForWaypoint(object, 2.0);
41+
// robotx_behavior_tree::ActionROS2Node::getPoint(object);
42+
EXPECT_EQ(true, true);
43+
}
44+
45+
/**
46+
* @brief Run all the tests that were declared with TEST()
47+
*
48+
* @param argc
49+
* @param argv
50+
* @return int
51+
*/
52+
int main(int argc, char ** argv)
53+
{
54+
testing::InitGoogleTest(&argc, argv);
55+
return RUN_ALL_TESTS();
56+
}
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
<root main_tree_to_execute = "MainTree" >
2+
<BehaviorTree ID="MainTree">
3+
<Sequence>
4+
<Action ID="MoveToFrontPoseOfObject" task_objects="{task_objects}" object_type="red_bouy"/>
5+
</Sequence>
6+
</BehaviorTree>
7+
</root>
Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
plugins:
2+
- package: robotx_behavior_tree
3+
name:
4+
- move_to_front_pose_of_object
5+
- move_goal_action
6+
behavior:
7+
description:
8+
package: robotx_bt_planner
9+
path : behavior_trees/move_to_front_pose_of_object.xml

0 commit comments

Comments
 (0)