Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Disable failing rdf test, merge #1163 and #1168 #1170

Merged
merged 4 commits into from
Apr 7, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 8 additions & 1 deletion moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,14 @@ void OMPLInterface::loadPlannerConfigurations()
<< rclcpp::to_string(parameter.get_type()) << "]");
continue;
}
specific_group_params[name] = parameter.value_to_string();
if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
specific_group_params[name] = parameter.as_string();
else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE)
specific_group_params[name] = moveit::core::toString(parameter.as_double());
else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
specific_group_params[name] = std::to_string(parameter.as_int());
else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_BOOL)
specific_group_params[name] = std::to_string(parameter.as_bool());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ def generate_launch_description():
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
"config",
"panda_ros2_controllers.yaml",
"ros2_controllers.yaml",
)
ros2_control_node = Node(
package="controller_manager",
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/launch/servo_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ def generate_launch_description():
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
"config",
"panda_ros2_controllers.yaml",
"ros2_controllers.yaml",
)
ros2_control_node = Node(
package="controller_manager",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ def generate_servo_test_description(
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
"config",
"panda_ros2_controllers.yaml",
"ros2_controllers.yaml",
)
ros2_control_node = Node(
package="controller_manager",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ def generate_servo_test_description(*args, gtest_name: SomeSubstitutionsType):
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
"config",
"panda_ros2_controllers.yaml",
"ros2_controllers.yaml",
)
ros2_control_node = Node(
package="controller_manager",
Expand Down
10 changes: 5 additions & 5 deletions moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,11 +74,9 @@ TEST(RDFIntegration, executor)
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("executor");

// Create a thread to spin an Executor.
std::thread([node]() {
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
executor.spin();
}).detach();
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
std::thread spinning_thread([&executor] { executor.spin(); });

// WHEN the RDFLoader is created
rdf_loader::RDFLoader loader(node, "topic_description");
Expand All @@ -88,6 +86,8 @@ TEST(RDFIntegration, executor)
EXPECT_EQ("gonzo", loader.getURDF()->name_);
ASSERT_NE(nullptr, loader.getSRDF());
EXPECT_EQ("gonzo", loader.getSRDF()->getName());
executor.cancel();
spinning_thread.join();
}

TEST(RDFIntegration, xacro_test)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def generate_move_group_test_description(*args, gtest_name: SomeSubstitutionsTyp
moveit_config = (
MoveItConfigsBuilder("moveit_resources_panda")
.robot_description(file_path="config/panda.urdf.xacro")
.trajectory_execution(file_path="config/panda_gripper_controllers.yaml")
.trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
.to_moveit_configs()
)

Expand Down Expand Up @@ -55,7 +55,7 @@ def generate_move_group_test_description(*args, gtest_name: SomeSubstitutionsTyp
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
"config",
"panda_ros2_controllers.yaml",
"ros2_controllers.yaml",
)
ros2_control_node = Node(
package="controller_manager",
Expand Down