Skip to content

Commit

Permalink
Port launch_testing depended unittests
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored and henningkayser committed Nov 8, 2021
1 parent 2dcb18d commit c97c840
Show file tree
Hide file tree
Showing 40 changed files with 1,552 additions and 1,001 deletions.
3 changes: 3 additions & 0 deletions moveit_planners/pilz_industrial_motion_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@
<test_depend>moveit_resources_prbt_moveit_config</test_depend>
<test_depend>moveit_resources_prbt_support</test_depend>
<test_depend>moveit_resources_prbt_pg70_support</test_depend>
<test_depend>moveit_configs_utils</test_depend>
<test_depend>parameter_builder</test_depend>
<test_depend>boost</test_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@

namespace pilz_industrial_motion_planner
{
static const std::string PARAM_NAMESPACE_LIMTS = "robot_description_planning";
static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner");

bool CommandPlanner::initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
Expand All @@ -67,11 +67,11 @@ bool CommandPlanner::initialize(const moveit::core::RobotModelConstPtr& model, c

// Obtain the aggregated joint limits
aggregated_limit_active_joints_ = pilz_industrial_motion_planner::JointLimitsAggregator::getAggregatedLimits(
node, PARAM_NAMESPACE_LIMTS, model->getActiveJointModels());
node, PARAM_NAMESPACE_LIMITS, model->getActiveJointModels());

// Obtain cartesian limits
cartesian_limit_ =
pilz_industrial_motion_planner::CartesianLimitsAggregator::getAggregatedLimits(node, PARAM_NAMESPACE_LIMTS);
pilz_industrial_motion_planner::CartesianLimitsAggregator::getAggregatedLimits(node, PARAM_NAMESPACE_LIMITS);

// Load the planning context loader
planner_context_loader.reset(new pluginlib::ClassLoader<PlanningContextLoader>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ find_package(ament_cmake_gmock REQUIRED)
find_package(ros_testing REQUIRED)
find_package(moveit_resources_prbt_support REQUIRED)
find_package(moveit_resources_prbt_moveit_config REQUIRED)
find_package(Boost REQUIRED thread)

find_package(${PROJECT_NAME}_testutils REQUIRED)

Expand All @@ -28,4 +29,6 @@ target_link_libraries(${PROJECT_NAME}_testhelpers ${PROJECT_NAME}_lib)
add_subdirectory(unit_tests)

# Integration tests
add_subdirectory(integration_tests)
add_subdirectory(integration_tests)
# Install test data
install(DIRECTORY test_data DESTINATION share/${PROJECT_NAME})

This file was deleted.

This file was deleted.

This file was deleted.

Loading

0 comments on commit c97c840

Please sign in to comment.