40#include <gmock/gmock.h>
41#include <gtest/gtest.h>
49using ::testing::AtLeast;
50using ::testing::Return;
51using ::testing::ReturnRef;
72 void SetUp()
override;
92 auto nse_ex = std::make_shared<NoSolverException>(
"");
93 EXPECT_EQ(nse_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
97 auto ex = std::make_shared<MoreThanOneTipFrameException>(
"");
98 EXPECT_EQ(ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
108 std::vector<std::string> tip_frames{
"fake_tip_frame1",
"fake_tip_frame2" };
110 EXPECT_CALL(jmg_mock_, getSolverInstance()).Times(AtLeast(1)).WillRepeatedly(Return(&solver_mock_));
112 EXPECT_CALL(solver_mock_, getTipFrames()).Times(AtLeast(1)).WillRepeatedly(ReturnRef(tip_frames));
114 EXPECT_THROW(getSolverTipFrame(&jmg_mock_), MoreThanOneTipFrameException);
123 EXPECT_CALL(jmg_mock_, getSolverInstance()).WillOnce(Return(
nullptr));
125 EXPECT_THROW(getSolverTipFrame(&jmg_mock_), NoSolverException);
135 EXPECT_THROW(hasSolver(group), std::invalid_argument);
142 testing::InitGoogleTest(&argc, argv);
144 return RUN_ALL_TESTS();
Test fixture for getSolverTipFrame tests.
JointModelGroupMock jmg_mock_
const std::string group_name_
MOCK_CONST_METHOD0(getName, const std::string &())
MOCK_CONST_METHOD0(getSolverInstance, const SolverMock *())
MOCK_CONST_METHOD0(getTipFrames, const std::vector< std::string > &())
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
int main(int argc, char **argv)