moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
integrationtest_plan_components_builder.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2019 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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#include <memory>
36#include <string>
37
38#include <gtest/gtest.h>
39
40#include <ros/ros.h>
41
44
47
48const std::string PARAM_PLANNING_GROUP_NAME("planning_group");
49const std::string ROBOT_DESCRIPTION_STR{ "robot_description" };
50const std::string EMPTY_VALUE{ "" };
51
52using namespace pilz_industrial_motion_planner;
53using namespace pilz_industrial_motion_planner;
54
55class IntegrationTestPlanComponentBuilder : public testing::Test
56{
57protected:
58 void SetUp() override;
59
60protected:
61 ros::NodeHandle ph_{ "~" };
63 planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };
64
65 std::string planning_group_;
66};
67
69{
70 if (!robot_model_)
71 {
72 FAIL() << "Robot model could not be loaded.";
73 }
74
75 ASSERT_TRUE(ph_.getParam(PARAM_PLANNING_GROUP_NAME, planning_group_));
76}
77
83TEST_F(IntegrationTestPlanComponentBuilder, TestExceptionErrorCodeMapping)
84{
85 auto nbs_ex = std::make_shared<NoBlenderSetException>("");
86 EXPECT_EQ(nbs_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
87
88 auto ntffse_ex = std::make_shared<NoTipFrameFunctionSetException>("");
89 EXPECT_EQ(ntffse_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
90
91 auto nrms_ex = std::make_shared<NoRobotModelSetException>("");
92 EXPECT_EQ(nrms_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
93
94 auto bf_ex = std::make_shared<BlendingFailedException>("");
95 EXPECT_EQ(bf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
96}
97
103{
104 robot_trajectory::RobotTrajectoryPtr traj{ new robot_trajectory::RobotTrajectory(robot_model_, planning_group_) };
105 PlanComponentsBuilder builder;
106
107 EXPECT_THROW(builder.append(planning_scene_, traj, 1.0), NoRobotModelSetException);
108}
109
115{
116 robot_trajectory::RobotTrajectoryPtr traj{ new robot_trajectory::RobotTrajectory(robot_model_, planning_group_) };
117 PlanComponentsBuilder builder;
118 builder.setModel(robot_model_);
119
120 builder.append(planning_scene_, traj, 0.0);
121
122 EXPECT_THROW(builder.append(planning_scene_, traj, 1.0), NoBlenderSetException);
123}
124
125int main(int argc, char** argv)
126{
127 ros::init(argc, argv, "integrationtest_plan_components_builder");
128 testing::InitGoogleTest(&argc, argv);
129
130 ros::NodeHandle nh;
131
132 return RUN_ALL_TESTS();
133}
Helper class to encapsulate the merge and blend process of trajectories.
void setModel(const moveit::core::RobotModelConstPtr &model)
Sets the robot model needed to create new trajectory elements.
void append(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_trajectory::RobotTrajectoryPtr &other, const double blend_radius)
Appends the specified trajectory to the trajectory container under construction.
This class maintains the representation of the environment as seen by a planning instance....
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
Maintain a sequence of waypoints and the time durations between these waypoints.
const std::string PARAM_PLANNING_GROUP_NAME("planning_group")
const std::string ROBOT_DESCRIPTION_STR
int main(int argc, char **argv)
const std::string EMPTY_VALUE
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.