moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_check_start_state_bounds.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2024, Sebastian Castro
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 PickNik 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: Sebastian Castro */
36 
37 #include <memory>
38 #include <string>
39 
40 #include <gmock/gmock.h>
41 #include <gtest/gtest.h>
42 #include <rclcpp/rclcpp.hpp>
43 
47 
48 class TestCheckStartStateBounds : public testing::Test
49 {
50 protected:
51  void SetUp() override
52  {
53  rclcpp::init(0, nullptr);
54  node_ = std::make_shared<rclcpp::Node>("test_check_start_state_bounds_adapter", "");
55 
56  // Load a robot model and place it in a planning scene.
57  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
58  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
59  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
60 
61  // Load the planning request adapter.
62  plugin_loader_ = std::make_unique<pluginlib::ClassLoader<planning_interface::PlanningRequestAdapter>>(
63  "moveit_core", "planning_interface::PlanningRequestAdapter");
64  adapter_ = plugin_loader_->createUniqueInstance("default_planning_request_adapters/CheckStartStateBounds");
65  adapter_->initialize(node_, "");
66  }
67 
68  void TearDown() override
69  {
70  rclcpp::shutdown();
71  }
72 
73  std::shared_ptr<rclcpp::Node> node_;
74  std::shared_ptr<planning_scene::PlanningScene> planning_scene_;
75  std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlanningRequestAdapter>> plugin_loader_;
76  pluginlib::UniquePtr<planning_interface::PlanningRequestAdapter> adapter_;
77 };
78 
80 {
82  request.group_name = "right_arm";
83  request.start_state.joint_state.name = {
84  "r_shoulder_pan_joint", "r_shoulder_lift_joint", "r_upper_arm_roll_joint", "r_forearm_roll_joint",
85  "r_elbow_flex_joint", "r_wrist_flex_joint", "r_wrist_roll_joint",
86  };
87  request.start_state.joint_state.position = {
88  0.0, 0.0, 0.0, 0.0, -0.5, -0.5, 0.0,
89  };
90 
91  const auto result = adapter_->adapt(planning_scene_, request);
92  EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
93  EXPECT_EQ(result.message, "");
94 }
95 
96 TEST_F(TestCheckStartStateBounds, TestRevoluteJointOutOfBounds)
97 {
99  request.group_name = "right_arm";
100  request.start_state.joint_state.name = {
101  "r_shoulder_pan_joint", "r_shoulder_lift_joint", "r_upper_arm_roll_joint", "r_forearm_roll_joint",
102  "r_elbow_flex_joint", "r_wrist_flex_joint", "r_wrist_roll_joint",
103  };
104  request.start_state.joint_state.position = {
105  1.0, // revolute joint out of bounds
106  0.0, 0.0, 0.0, -0.5, -0.5, 0.0,
107  };
108 
109  const auto result = adapter_->adapt(planning_scene_, request);
110  EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID);
111  EXPECT_EQ(result.message, "Start state out of bounds.");
112 }
113 
114 TEST_F(TestCheckStartStateBounds, TestContinuousJointOutOfBounds)
115 {
117  request.group_name = "right_arm";
118  request.start_state.joint_state.name = {
119  "r_shoulder_pan_joint", "r_shoulder_lift_joint", "r_upper_arm_roll_joint", "r_forearm_roll_joint",
120  "r_elbow_flex_joint", "r_wrist_flex_joint", "r_wrist_roll_joint",
121  };
122  request.start_state.joint_state.position = {
123  0.0, 0.0, 0.0, 100.0, // continuous joint out of bounds
124  -0.5, -0.5, 0.0,
125  };
126 
127  const auto result = adapter_->adapt(planning_scene_, request);
128  EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID);
129  EXPECT_EQ(result.message, "Start state out of bounds.");
130 }
131 
132 TEST_F(TestCheckStartStateBounds, TestContinuousJointFixedBounds)
133 {
135  request.group_name = "right_arm";
136  request.start_state.joint_state.name = {
137  "r_shoulder_pan_joint", "r_shoulder_lift_joint", "r_upper_arm_roll_joint", "r_forearm_roll_joint",
138  "r_elbow_flex_joint", "r_wrist_flex_joint", "r_wrist_roll_joint",
139  };
140  request.start_state.joint_state.position = {
141  0.0, 0.0, 0.0, 100.0, // continuous joint out of bounds
142  -0.5, -0.5, 0.0,
143  };
144 
145  // Modify the start state. The adapter should succeed.
146  node_->set_parameter(rclcpp::Parameter("fix_start_state", true));
147 
148  const auto result = adapter_->adapt(planning_scene_, request);
149  EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
150  EXPECT_EQ(result.message, "Normalized start state.");
151 
152  // Validate that the large continuous joint position value in the request start state was normalized.
153  const auto& joint_names = request.start_state.joint_state.name;
154  const size_t joint_idx =
155  std::find(joint_names.begin(), joint_names.end(), "r_forearm_roll_joint") - joint_names.begin();
156  EXPECT_NEAR(request.start_state.joint_state.position[joint_idx], -0.530965, 1.0e-4);
157 }
158 
159 int main(int argc, char** argv)
160 {
161  ::testing::InitGoogleTest(&argc, argv);
162  return RUN_ALL_TESTS();
163 }
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlanningRequestAdapter > > plugin_loader_
std::shared_ptr< rclcpp::Node > node_
pluginlib::UniquePtr< planning_interface::PlanningRequestAdapter > adapter_
std::shared_ptr< planning_scene::PlanningScene > planning_scene_
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
int main(int argc, char **argv)
TEST_F(TestCheckStartStateBounds, TestWithinBounds)