1 #include <gtest/gtest.h> 27 ROS_INFO_STREAM(
"Succesfuly create the test setup to load faulty params.");
58 int main(
int argc,
char** argv)
60 ros::init(argc, argv,
"moveit_opw_kinematics_test_fanuc");
61 testing::InitGoogleTest(&argc, argv);
62 return RUN_ALL_TESTS();
const std::string GROUP_PARAM
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const std::string ROBOT_DESCRIPTION
const std::string TIP_LINK_PARAM
#define EXPECT_FALSE(args)
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization) override
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
std::string robot_description_name_
TEST_F(TestPlugin, InitFaulty)
moveit_opw_kinematics_plugin::MoveItOPWKinematicsPlugin plugin_
#define ROS_INFO_STREAM(args)
const std::string ROOT_LINK_PARAM
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)