38#include <gtest/gtest.h>
58 void SetUp()
override;
61 ros::NodeHandle
ph_{
"~" };
72 FAIL() <<
"Robot model could not be loaded.";
85 auto nbs_ex = std::make_shared<NoBlenderSetException>(
"");
86 EXPECT_EQ(nbs_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
88 auto ntffse_ex = std::make_shared<NoTipFrameFunctionSetException>(
"");
89 EXPECT_EQ(ntffse_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
91 auto nrms_ex = std::make_shared<NoRobotModelSetException>(
"");
92 EXPECT_EQ(nrms_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
94 auto bf_ex = std::make_shared<BlendingFailedException>(
"");
95 EXPECT_EQ(bf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
107 EXPECT_THROW(builder.
append(planning_scene_, traj, 1.0), NoRobotModelSetException);
120 builder.
append(planning_scene_, traj, 0.0);
122 EXPECT_THROW(builder.
append(planning_scene_, traj, 1.0), NoBlenderSetException);
127 ros::init(argc, argv,
"integrationtest_plan_components_builder");
128 testing::InitGoogleTest(&argc, argv);
132 return RUN_ALL_TESTS();
robot_model::RobotModelConstPtr robot_model_
std::string planning_group_
planning_scene::PlanningSceneConstPtr planning_scene_
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.