40 #include <gtest/gtest.h>
56 void SetUp()
override;
68 FAIL() <<
"Robot model could not be loaded.";
78 EXPECT_TRUE(hasSolver(robot_model_->getJointModelGroup(
"manipulator"))) <<
"hasSolver returns false for manipulator";
86 EXPECT_FALSE(hasSolver(robot_model_->getJointModelGroup(
"gripper"))) <<
"hasSolver returns true for gripper";
95 getSolverTipFrame(robot_model_->getJointModelGroup(
"manipulator"));
103 EXPECT_THROW(getSolverTipFrame(robot_model_->getJointModelGroup(
"gripper")), NoSolverException);
108 int main(
int argc,
char** argv)
110 ros::init(argc, argv,
"integrationtest_get_solver_tip_frame");
111 testing::InitGoogleTest(&argc, argv);
115 return RUN_ALL_TESTS();
robot_model::RobotModelConstPtr robot_model_
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
int main(int argc, char **argv)
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
const std::string ROBOT_DESCRIPTION_PARAM