test_planning_request_adapter_chain.cpp
Go to the documentation of this file.
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 <gtest/gtest.h>
40 
42 {
43 public:
44  void initialize(ros::NodeHandle const& /*node_handle*/) override
45  {
46  }
47  bool adaptAndPlan(PlannerFn const& planner, planning_scene::PlanningSceneConstPtr const& planning_scene,
49  std::vector<std::size_t>& added_path_index) const override
50  {
51  bool success = planner(planning_scene, req, res);
52  if (success)
53  {
54  res.trajectory_->addSuffixWayPoint(res.trajectory_->getLastWayPoint(), 1);
55  added_path_index.push_back(res.trajectory_->getWayPointCount() - 1);
56  }
57  return success;
58  }
59 };
60 
62 {
63 public:
64  void initialize(ros::NodeHandle const& /*node_handle*/) override
65  {
66  }
67  bool adaptAndPlan(PlannerFn const& planner, planning_scene::PlanningSceneConstPtr const& planning_scene,
69  std::vector<std::size_t>& added_path_index) const override
70  {
71  bool success = planner(planning_scene, req, res);
72  if (success)
73  {
74  res.trajectory_->addPrefixWayPoint(res.trajectory_->getFirstWayPoint(), 0);
75  added_path_index.push_back(0);
76  }
77  return success;
78  }
79 };
80 
82 {
83 public:
84  PlannerManagerStub(planning_interface::PlanningContextPtr planningContext)
85  : m_planningContext{ std::move(planningContext) }
86  {
87  }
88  planning_interface::PlanningContextPtr
89  getPlanningContext(planning_scene::PlanningSceneConstPtr const& /*planning_scene*/,
91  moveit_msgs::MoveItErrorCodes& /*error*/) const override
92  {
93  return m_planningContext;
94  }
95 
96  bool canServiceRequest(planning_interface::MotionPlanRequest const& /*req*/) const override
97  {
98  return true;
99  }
100 
101 private:
102  planning_interface::PlanningContextPtr m_planningContext;
103 };
104 
106 {
107 public:
109 
110  void setTrajectory(robot_trajectory::RobotTrajectoryPtr trajectory)
111  {
112  m_trajectory = std::move(trajectory);
113  }
114 
116  {
117  if (!m_trajectory)
118  return false;
119 
121  return true;
122  }
123 
125  {
126  if (!m_trajectory)
127  return false;
128 
129  res.trajectory_.push_back(m_trajectory);
130  return true;
131  }
132 
133  bool terminate() override
134  {
135  return true;
136  }
137 
138  void clear() override
139  {
140  }
141 
142 private:
143  robot_trajectory::RobotTrajectoryPtr m_trajectory;
144 };
145 
146 class PlanningRequestAdapterTests : public testing::Test
147 {
148 protected:
149  void SetUp() override
150  {
152  group_name_ = "panda_arm";
153  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
154  planning_context_ = std::make_shared<PlanningContextStub>("stub", group_name_);
155  planner_manager_ = std::make_shared<PlannerManagerStub>(planning_context_);
156  }
157 
158  robot_trajectory::RobotTrajectoryPtr createRandomTrajectory(std::size_t waypointCount)
159  {
160  robot_trajectory::RobotTrajectoryPtr robot_trajectory =
161  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, group_name_);
162  for (std::size_t i = 0; i < waypointCount; ++i)
163  robot_trajectory->addSuffixWayPoint(std::make_shared<robot_state::RobotState>(robot_model_), 1.);
164  return robot_trajectory;
165  }
166 
167 protected:
168  std::string group_name_;
170  moveit::core::RobotModelPtr robot_model_;
171  planning_scene::PlanningScenePtr planning_scene_;
172  std::shared_ptr<PlanningContextStub> planning_context_;
173  std::shared_ptr<PlannerManagerStub> planner_manager_;
174 };
175 
176 TEST_F(PlanningRequestAdapterTests, testMergeAddedPathIndex)
177 {
178  sut_.addAdapter(std::make_shared<AppendingPlanningRequestAdapter>());
179  sut_.addAdapter(std::make_shared<PrependingPlanningRequestAdapter>());
180  sut_.addAdapter(std::make_shared<AppendingPlanningRequestAdapter>());
181 
182  planning_context_->setTrajectory(createRandomTrajectory(4));
183 
185  req.group_name = group_name_;
187  std::vector<std::size_t> added_path_index;
188  sut_.adaptAndPlan(planner_manager_, planning_scene_, req, res, added_path_index);
189 
190  ASSERT_EQ(added_path_index.size(), 3UL);
191  EXPECT_EQ(added_path_index[0], 0UL);
192  EXPECT_EQ(added_path_index[1], 5UL);
193  EXPECT_EQ(added_path_index[2], 6UL);
194 }
195 
196 int main(int argc, char** argv)
197 {
198  testing::InitGoogleTest(&argc, argv);
199  return RUN_ALL_TESTS();
200 }
PlanningContextStub
Definition: test_planning_request_adapter_chain.cpp:105
PlanningContextStub::terminate
bool terminate() override
If solve() is running, terminate the computation. Return false if termination not possible....
Definition: test_planning_request_adapter_chain.cpp:133
PlannerManagerStub
Definition: test_planning_request_adapter_chain.cpp:81
PlannerManagerStub::canServiceRequest
bool canServiceRequest(planning_interface::MotionPlanRequest const &) const override
Determine whether this plugin instance is able to represent this planning request.
Definition: test_planning_request_adapter_chain.cpp:96
PlanningRequestAdapterTests::sut_
planning_request_adapter::PlanningRequestAdapterChain sut_
Definition: test_planning_request_adapter_chain.cpp:169
PlanningRequestAdapterTests::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: test_planning_request_adapter_chain.cpp:170
planning_interface::MotionPlanResponse
Definition: planning_response.h:78
PlanningRequestAdapterTests::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: test_planning_request_adapter_chain.cpp:171
PrependingPlanningRequestAdapter
Definition: test_planning_request_adapter_chain.cpp:61
PrependingPlanningRequestAdapter::adaptAndPlan
bool adaptAndPlan(PlannerFn const &planner, planning_scene::PlanningSceneConstPtr const &planning_scene, planning_interface::MotionPlanRequest const &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
Definition: test_planning_request_adapter_chain.cpp:67
PlanningContextStub::setTrajectory
void setTrajectory(robot_trajectory::RobotTrajectoryPtr trajectory)
Definition: test_planning_request_adapter_chain.cpp:110
planning_request_adapter::PlanningRequestAdapter
Definition: planning_request_adapter.h:81
planning_request_adapter::PlanningRequestAdapterChain
Apply a sequence of adapters to a motion plan.
Definition: planning_request_adapter.h:128
planning_request_adapter.h
robot_trajectory
Definition: robot_trajectory.h:46
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
Definition: planning_response.h:112
AppendingPlanningRequestAdapter
Definition: test_planning_request_adapter_chain.cpp:41
PlanningContextStub::m_trajectory
robot_trajectory::RobotTrajectoryPtr m_trajectory
Definition: test_planning_request_adapter_chain.cpp:143
planning_interface::MotionPlanDetailedResponse::trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
Definition: planning_response.h:131
PlanningRequestAdapterTests::planner_manager_
std::shared_ptr< PlannerManagerStub > planner_manager_
Definition: test_planning_request_adapter_chain.cpp:173
PrependingPlanningRequestAdapter::initialize
void initialize(ros::NodeHandle const &) override
Initialize parameters using the passed NodeHandle if no initialization is needed, simply implement as...
Definition: test_planning_request_adapter_chain.cpp:64
PlannerManagerStub::m_planningContext
planning_interface::PlanningContextPtr m_planningContext
Definition: test_planning_request_adapter_chain.cpp:102
PlannerManagerStub::PlannerManagerStub
PlannerManagerStub(planning_interface::PlanningContextPtr planningContext)
Definition: test_planning_request_adapter_chain.cpp:84
PlanningContextStub::solve
bool solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
Definition: test_planning_request_adapter_chain.cpp:115
main
int main(int argc, char **argv)
Definition: test_planning_request_adapter_chain.cpp:196
PlanningContextStub::clear
void clear() override
Clear the data structures used by the planner.
Definition: test_planning_request_adapter_chain.cpp:138
PlannerManagerStub::getPlanningContext
planning_interface::PlanningContextPtr getPlanningContext(planning_scene::PlanningSceneConstPtr const &, planning_interface::MotionPlanRequest const &, moveit_msgs::MoveItErrorCodes &) const override
Construct a planning context given the current scene and a planning request. If a problem is encounte...
Definition: test_planning_request_adapter_chain.cpp:89
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
Definition: planning_request.h:77
PlanningRequestAdapterTests::SetUp
void SetUp() override
Definition: test_planning_request_adapter_chain.cpp:149
PlanningRequestAdapterTests
Definition: test_planning_request_adapter_chain.cpp:146
robot_model_test_utils.h
PlanningRequestAdapterTests::planning_context_
std::shared_ptr< PlanningContextStub > planning_context_
Definition: test_planning_request_adapter_chain.cpp:172
TEST_F
TEST_F(PlanningRequestAdapterTests, testMergeAddedPathIndex)
Definition: test_planning_request_adapter_chain.cpp:176
planning_request_adapter::PlanningRequestAdapter::PlannerFn
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Definition: planning_request_adapter.h:86
planning_interface::PlanningContext::PlanningContext
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
Definition: planning_interface.cpp:91
AppendingPlanningRequestAdapter::adaptAndPlan
bool adaptAndPlan(PlannerFn const &planner, planning_scene::PlanningSceneConstPtr const &planning_scene, planning_interface::MotionPlanRequest const &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
Definition: test_planning_request_adapter_chain.cpp:79
PlanningContextStub::solve
bool solve(planning_interface::MotionPlanDetailedResponse &res) override
Solve the motion planning problem and store the detailed result in res. This function should not clea...
Definition: test_planning_request_adapter_chain.cpp:124
AppendingPlanningRequestAdapter::initialize
void initialize(ros::NodeHandle const &) override
Initialize parameters using the passed NodeHandle if no initialization is needed, simply implement as...
Definition: test_planning_request_adapter_chain.cpp:76
planning_interface::PlanningContext
Representation of a particular planning context – the planning scene and the request are known,...
Definition: planning_interface.h:80
planning_scene
This namespace includes the central class for representing planning scenes.
Definition: planning_interface.h:45
PlanningRequestAdapterTests::group_name_
std::string group_name_
Definition: test_planning_request_adapter_chain.cpp:168
PlanningRequestAdapterTests::createRandomTrajectory
robot_trajectory::RobotTrajectoryPtr createRandomTrajectory(std::size_t waypointCount)
Definition: test_planning_request_adapter_chain.cpp:158
EXPECT_EQ
#define EXPECT_EQ(a, b)
planning_interface::PlannerManager
Base class for a MoveIt planner.
Definition: planning_interface.h:150
ros::NodeHandle
planning_interface::MotionPlanDetailedResponse
Definition: planning_response.h:127
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
Definition: robot_model_test_utils.cpp:117


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:41