|
| 1 | +/********************************************************************* |
| 2 | + * Software License Agreement (BSD License) |
| 3 | + * |
| 4 | + * Copyright (c) 2023, Willow Garage, Inc. |
| 5 | + * All rights reserved. |
| 6 | + * |
| 7 | + * Redistribution and use in source and binary forms, with or without |
| 8 | + * modification, are permitted provided that the following conditions |
| 9 | + * are met: |
| 10 | + * |
| 11 | + * * Redistributions of source code must retain the above copyright |
| 12 | + * notice, this list of conditions and the following disclaimer. |
| 13 | + * * Redistributions in binary form must reproduce the above |
| 14 | + * copyright notice, this list of conditions and the following |
| 15 | + * disclaimer in the documentation and/or other materials provided |
| 16 | + * with the distribution. |
| 17 | + * * Neither the name of Willow Garage nor the names of its |
| 18 | + * contributors may be used to endorse or promote products derived |
| 19 | + * from this software without specific prior written permission. |
| 20 | + * |
| 21 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 22 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 23 | + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 24 | + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 25 | + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 26 | + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 27 | + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 28 | + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 29 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 30 | + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 31 | + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 32 | + * POSSIBILITY OF SUCH DAMAGE. |
| 33 | + *********************************************************************/ |
| 34 | + |
| 35 | +/* Author: Hugo Laloge */ |
| 36 | + |
| 37 | +#include <gmock/gmock.h> |
| 38 | +#include <moveit/utils/robot_model_test_utils.h> |
| 39 | +#include <moveit/planning_request_adapter/planning_request_adapter.h> |
| 40 | + |
| 41 | +class AppendingPlanningRequestAdapter final : public planning_request_adapter::PlanningRequestAdapter |
| 42 | +{ |
| 43 | +public: |
| 44 | + void initialize(const rclcpp::Node::SharedPtr& /*node*/, const std::string& /*parameter_namespace*/) override |
| 45 | + { |
| 46 | + } |
| 47 | + bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene, |
| 48 | + const planning_interface::MotionPlanRequest& req, |
| 49 | + planning_interface::MotionPlanResponse& res) const override |
| 50 | + { |
| 51 | + bool success = planner(planning_scene, req, res); |
| 52 | + if (success) |
| 53 | + { |
| 54 | + res.trajectory->addSuffixWayPoint(res.trajectory->getLastWayPoint(), 1); |
| 55 | + res.added_path_index.push_back(res.trajectory->getWayPointCount() - 1); |
| 56 | + } |
| 57 | + return success; |
| 58 | + } |
| 59 | + std::string getDescription() const override |
| 60 | + { |
| 61 | + return "AppendingPlanningRequestAdapter"; |
| 62 | + } |
| 63 | +}; |
| 64 | + |
| 65 | +class PrependingPlanningRequestAdapter final : public planning_request_adapter::PlanningRequestAdapter |
| 66 | +{ |
| 67 | +public: |
| 68 | + void initialize(const rclcpp::Node::SharedPtr& /*node*/, const std::string& /*parameter_namespace*/) override |
| 69 | + { |
| 70 | + } |
| 71 | + bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene, |
| 72 | + const planning_interface::MotionPlanRequest& req, |
| 73 | + planning_interface::MotionPlanResponse& res) const override |
| 74 | + { |
| 75 | + bool success = planner(planning_scene, req, res); |
| 76 | + if (success) |
| 77 | + { |
| 78 | + res.trajectory->addPrefixWayPoint(res.trajectory->getFirstWayPoint(), 0); |
| 79 | + res.added_path_index.push_back(0); |
| 80 | + } |
| 81 | + return success; |
| 82 | + } |
| 83 | + std::string getDescription() const override |
| 84 | + { |
| 85 | + return "PrependingPlanningRequestAdapter"; |
| 86 | + } |
| 87 | +}; |
| 88 | + |
| 89 | +class PlannerManagerStub : public planning_interface::PlannerManager |
| 90 | +{ |
| 91 | +public: |
| 92 | + PlannerManagerStub(planning_interface::PlanningContextPtr planningContext) |
| 93 | + : m_planningContext_{ std::move(planningContext) } |
| 94 | + { |
| 95 | + } |
| 96 | + planning_interface::PlanningContextPtr |
| 97 | + getPlanningContext(const planning_scene::PlanningSceneConstPtr& /*planning_scene*/, |
| 98 | + const planning_interface::MotionPlanRequest& /*req*/, |
| 99 | + moveit_msgs::msg::MoveItErrorCodes& /*error*/) const override |
| 100 | + { |
| 101 | + return m_planningContext_; |
| 102 | + } |
| 103 | + |
| 104 | + bool canServiceRequest(const planning_interface::MotionPlanRequest& /*req*/) const override |
| 105 | + { |
| 106 | + return true; |
| 107 | + } |
| 108 | + |
| 109 | +private: |
| 110 | + planning_interface::PlanningContextPtr m_planningContext_; |
| 111 | +}; |
| 112 | + |
| 113 | +class PlanningContextStub : public planning_interface::PlanningContext |
| 114 | +{ |
| 115 | +public: |
| 116 | + using planning_interface::PlanningContext::PlanningContext; |
| 117 | + |
| 118 | + void setTrajectory(robot_trajectory::RobotTrajectoryPtr trajectory) |
| 119 | + { |
| 120 | + m_trajectory_ = std::move(trajectory); |
| 121 | + } |
| 122 | + |
| 123 | + bool solve(planning_interface::MotionPlanResponse& res) override |
| 124 | + { |
| 125 | + if (!m_trajectory_) |
| 126 | + return false; |
| 127 | + |
| 128 | + res.trajectory = m_trajectory_; |
| 129 | + return true; |
| 130 | + } |
| 131 | + |
| 132 | + bool solve(planning_interface::MotionPlanDetailedResponse& res) override |
| 133 | + { |
| 134 | + if (!m_trajectory_) |
| 135 | + return false; |
| 136 | + |
| 137 | + res.trajectory.push_back(m_trajectory_); |
| 138 | + return true; |
| 139 | + } |
| 140 | + |
| 141 | + bool terminate() override |
| 142 | + { |
| 143 | + return true; |
| 144 | + } |
| 145 | + |
| 146 | + void clear() override |
| 147 | + { |
| 148 | + } |
| 149 | + |
| 150 | +private: |
| 151 | + robot_trajectory::RobotTrajectoryPtr m_trajectory_; |
| 152 | +}; |
| 153 | + |
| 154 | +class PlanningRequestAdapterTests : public testing::Test |
| 155 | +{ |
| 156 | +protected: |
| 157 | + void SetUp() override |
| 158 | + { |
| 159 | + robot_model_ = moveit::core::loadTestingRobotModel("panda"); |
| 160 | + group_name_ = "panda_arm"; |
| 161 | + planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_); |
| 162 | + planning_context_ = std::make_shared<PlanningContextStub>("stub", group_name_); |
| 163 | + planner_manager_ = std::make_shared<PlannerManagerStub>(planning_context_); |
| 164 | + } |
| 165 | + |
| 166 | + robot_trajectory::RobotTrajectoryPtr createRandomTrajectory(std::size_t waypointCount) |
| 167 | + { |
| 168 | + robot_trajectory::RobotTrajectoryPtr robot_trajectory = |
| 169 | + std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, group_name_); |
| 170 | + for (std::size_t i = 0; i < waypointCount; ++i) |
| 171 | + robot_trajectory->addSuffixWayPoint(std::make_shared<moveit::core::RobotState>(robot_model_), 1.); |
| 172 | + return robot_trajectory; |
| 173 | + } |
| 174 | + |
| 175 | +protected: |
| 176 | + std::string group_name_; |
| 177 | + planning_request_adapter::PlanningRequestAdapterChain sut_; |
| 178 | + moveit::core::RobotModelPtr robot_model_; |
| 179 | + planning_scene::PlanningScenePtr planning_scene_; |
| 180 | + std::shared_ptr<PlanningContextStub> planning_context_; |
| 181 | + std::shared_ptr<PlannerManagerStub> planner_manager_; |
| 182 | +}; |
| 183 | + |
| 184 | +TEST_F(PlanningRequestAdapterTests, testMergeAddedPathIndex) |
| 185 | +{ |
| 186 | + sut_.addAdapter(std::make_shared<AppendingPlanningRequestAdapter>()); |
| 187 | + sut_.addAdapter(std::make_shared<PrependingPlanningRequestAdapter>()); |
| 188 | + sut_.addAdapter(std::make_shared<AppendingPlanningRequestAdapter>()); |
| 189 | + |
| 190 | + planning_context_->setTrajectory(createRandomTrajectory(4)); |
| 191 | + |
| 192 | + planning_interface::MotionPlanRequest req; |
| 193 | + req.group_name = group_name_; |
| 194 | + planning_interface::MotionPlanResponse res; |
| 195 | + std::ignore = sut_.adaptAndPlan(planner_manager_, planning_scene_, req, res); |
| 196 | + |
| 197 | + EXPECT_THAT(res.added_path_index, testing::ElementsAre(0, 5, 6)); |
| 198 | +} |
| 199 | + |
| 200 | +int main(int argc, char** argv) |
| 201 | +{ |
| 202 | + testing::InitGoogleTest(&argc, argv); |
| 203 | + return RUN_ALL_TESTS(); |
| 204 | +} |
0 commit comments