41 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"test_controllers");
54 MoveItSetupTest::SetUp();
55 config_data_->registerType(
"moveit_controllers",
"moveit_setup::controllers::MoveItControllersConfig");
56 config_data_->registerType(
"ros2_controllers",
"moveit_setup::controllers::ROS2ControllersConfig");
57 config_data_->registerType(
"modified_urdf",
"moveit_setup::ModifiedUrdfConfig");
58 config_data_->registerType(
"control_xacro",
"moveit_setup::controllers::ControlXacroConfig");
64 config_data_->preloadWithFullConfig(
"moveit_resources_fanuc_moveit_config");
66 const std::vector<ControllerInfo>& controllers = ros2_controllers_config->
getControllers();
67 ASSERT_EQ(1u, controllers.size());
69 EXPECT_EQ(
"fanuc_controller", ci.
name_);
70 EXPECT_EQ(
"joint_trajectory_controller/JointTrajectoryController", ci.
type_);
71 EXPECT_EQ(6u, ci.
joints_.size());
74 const std::vector<ControllerInfo>& mcontrollers = moveit_controllers_config->
getControllers();
75 ASSERT_EQ(1u, mcontrollers.size());
77 EXPECT_EQ(
"fanuc_controller", mci.
name_);
78 EXPECT_EQ(
"FollowJointTrajectory", mci.
type_);
79 EXPECT_EQ(6u, mci.
joints_.size());
84 config_data_->preloadWithFullConfig(
"moveit_resources_panda_moveit_config");
86 const std::vector<ControllerInfo>& controllers = ros2_controllers_config->
getControllers();
87 ASSERT_EQ(2u, controllers.size());
89 int offset = controllers[0].name_ ==
"panda_arm_controller" ? 0 : 1;
91 EXPECT_EQ(
"panda_arm_controller", ci1.
name_);
92 EXPECT_EQ(
"joint_trajectory_controller/JointTrajectoryController", ci1.
type_);
93 EXPECT_EQ(7u, ci1.
joints_.size());
96 EXPECT_EQ(
"panda_hand_controller", ci2.
name_);
97 EXPECT_EQ(
"position_controllers/GripperActionController", ci2.
type_);
98 EXPECT_EQ(1u, ci2.
joints_.size());
115 config_data_->preloadWithFullConfig(
"moveit_resources_fanuc_moveit_config");
117 generateFiles<ROS2ControllersConfig>(
"ros2_controllers");
118 generateFiles<MoveItControllersConfig>(
"moveit_controllers");
120 std::filesystem::path original_config =
getSharePath(
"moveit_resources_fanuc_moveit_config");
121 for (
const std::string relative_path : {
"config/moveit_controllers.yaml",
"config/ros2_controllers.yaml" })
130 auto config_dir =
getSharePath(
"moveit_resources_panda_moveit_config");
131 YAML::Node settings = YAML::LoadFile(config_dir /
".setup_assistant")[
"moveit_setup_assistant_config"];
134 srdf_config->
loadPrevious(config_dir, settings[
"SRDF"]);
139 EXPECT_EQ(ros2_controllers_config->getControllers().size(), 0u);
143 initializeStep(setup_step);
149 size_t group_count = srdf_config->getGroups().size();
152 EXPECT_EQ(ros2_controllers_config->getControllers().size(), group_count);
155 int main(
int argc,
char** argv)
157 testing::InitGoogleTest(&argc, argv);
158 rclcpp::init(argc, argv);
159 return RUN_ALL_TESTS();
Test environment with DataWarehouse setup and help for generating files in a temp dir.
moveit_setup::DataWarehousePtr config_data_
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
std::vector< ControllerInfo > & getControllers()
Gets controllers_ vector.
bool addDefaultControllers()
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
void expectYamlEquivalence(const YAML::Node &generated, const YAML::Node &reference, const std::filesystem::path &generated_path, const std::string &yaml_namespace="")
const rclcpp::Logger LOGGER
std::vector< std::string > joints_
TEST_F(ControllersTest, ParseFanuc)
int main(int argc, char **argv)