test_faulty_params.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <ros/ros.h>
3 
9 
10 // Names to read values from the parameter server
11 const std::string GROUP_PARAM = "group";
12 const std::string TIP_LINK_PARAM = "tip_link";
13 const std::string ROOT_LINK_PARAM = "root_link";
14 
15 // Robot description almost always called "robot_description" and therefore hardcoded below
16 const std::string ROBOT_DESCRIPTION = "robot_description";
17 
18 class TestPlugin : public ::testing::Test
19 {
20 protected:
21  void SetUp() override
22  {
23  ros::NodeHandle nh;
26  {
27  ROS_INFO_STREAM("Succesfuly create the test setup to load faulty params.");
28  }
29  else
30  {
31  ROS_ERROR_STREAM("Failed to load parameters necessary to load plugin.");
32  }
33  }
34  void TearDown() override
35  {
36  }
37 
39  std::string root_link_;
40  std::string tip_link_;
41  std::string group_name_;
43 };
44 
51 TEST_F(TestPlugin, InitFaulty)
52 {
53  // the last parameter specifies "search_discretization", which is not used by the opw plugin
55  EXPECT_FALSE(res);
56 }
57 
58 int main(int argc, char** argv)
59 {
60  ros::init(argc, argv, "moveit_opw_kinematics_test_fanuc");
61  testing::InitGoogleTest(&argc, argv);
62  return RUN_ALL_TESTS();
63 }
const std::string GROUP_PARAM
void TearDown() override
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const std::string ROBOT_DESCRIPTION
void SetUp() override
const std::string TIP_LINK_PARAM
std::string tip_link_
#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_
std::string root_link_
#define ROS_INFO_STREAM(args)
const std::string ROOT_LINK_PARAM
bool getParam(const std::string &key, std::string &s) const
std::string group_name_
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)


moveit_opw_kinematics_plugin
Author(s): Jeroen De Maeyer, Simon Schmeisser (isys vision)
autogenerated on Wed Jun 3 2020 03:17:14