Skip to content

Commit

Permalink
Cleanup and use correct cmake macros
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored and henningkayser committed Oct 5, 2021
1 parent 03e3a09 commit e7ed187
Show file tree
Hide file tree
Showing 6 changed files with 10 additions and 64 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -319,7 +319,6 @@ inline bool getJointLimits(const std::string& joint_name, const rclcpp::Node::Sh
return false; // LCOV_EXCL_LINE // The case where getJointLimits returns
// false is covered above.
}

try
{
// Deceleration limits
Expand All @@ -328,7 +327,7 @@ inline bool getJointLimits(const std::string& joint_name, const rclcpp::Node::Sh
if (limits.has_deceleration_limits)
{
limits.max_deceleration =
node->declare_parameter(limits_namespace + ".max_deceleration", limits.max_deceleration);
node->declare_parameter(limits_namespace + ".max_deceleration", std::numeric_limits<double>::quiet_NaN());
}
}
catch (const std::exception& ex)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,15 +58,16 @@ bool declareAndGetParam(double& output_value, const std::string& param_name, con
node->get_parameter<double>(param_name, output_value);
if (std::isnan(output_value))
{
RCLCPP_ERROR(node->get_logger(), "Parameter \'%s\', is not set in the config file.", param_name);
RCLCPP_ERROR(node->get_logger(), "Parameter \'%s\', is not set in the config file.", param_name.c_str());
return false;
}
return true;
}
catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
{
RCLCPP_WARN(node->get_logger(), "InvalidParameterTypeException(\'%s\'): ", param_name, e.what());
RCLCPP_ERROR(node->get_logger(), "Error getting parameter \'%s\', check parameter type in YAML file", param_name);
RCLCPP_WARN(node->get_logger(), "InvalidParameterTypeException(\'%s\'): %s", param_name.c_str(), e.what());
RCLCPP_ERROR(node->get_logger(), "Error getting parameter \'%s\', check parameter type in YAML file",
param_name.c_str());
throw e;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,22 +20,21 @@ set(UNIT_TEST_SOURCEFILES
)

# Direct Command Planner Unit Test
ament_add_gtest_executable(unittest_pilz_industrial_motion_planner_direct
ament_add_gtest(unittest_pilz_industrial_motion_planner_direct
src/unittest_pilz_industrial_motion_planner.cpp
${CMAKE_SOURCE_DIR}/src/planning_context_loader_ptp.cpp)
target_link_libraries(unittest_pilz_industrial_motion_planner_direct ${PROJECT_NAME}_lib ${PROJECT_NAME}_testhelpers)

# Asymmetric Trapezoidal Velocity Profile Unit Test
ament_add_gtest_executable(unittest_velocity_profile_atrap
ament_add_gtest(unittest_velocity_profile_atrap
src/unittest_velocity_profile_atrap.cpp
${CMAKE_SOURCE_DIR}/src/velocity_profile_atrap.cpp)
target_link_libraries(unittest_velocity_profile_atrap ${PROJECT_NAME}_lib)

# Trajectory Generator Unit Test
ament_add_gtest_executable(unittest_trajectory_generator
ament_add_gtest(unittest_trajectory_generator
src/unittest_trajectory_generator.cpp
${CMAKE_SOURCE_DIR}/src/trajectory_generator.cpp)
ament_target_dependencies(unittest_trajectory_generator rclcpp ${PROJECT_NAME}_testutils)
target_link_libraries(unittest_trajectory_generator ${PROJECT_NAME}_lib)

# # Trajectory Functions Unit Test
Expand Down Expand Up @@ -126,12 +125,12 @@ add_ros_test(launch/unittest_joint_limit.test.py ARGS "test_binary_dir:=${CMAKE_
# )

# JointLimitsContainer Unit Test
ament_add_gtest_executable(unittest_joint_limits_container
ament_add_gtest(unittest_joint_limits_container
src/unittest_joint_limits_container.cpp)
target_link_libraries(unittest_joint_limits_container ${PROJECT_NAME}_lib)

# JointLimitsValidator Unit Test
ament_add_gtest_executable(unittest_joint_limits_validator
ament_add_gtest(unittest_joint_limits_validator
src/unittest_joint_limits_validator.cpp)
target_link_libraries(unittest_joint_limits_validator ${PROJECT_NAME}_lib)

Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,6 @@ TEST_F(JointLimitTest, SimpleRead)

EXPECT_EQ(1, joint_limits_extended.max_acceleration);
EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
EXPECT_EQ(1, joint_limits_extended.max_acceleration);
EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
EXPECT_EQ(1, joint_limits_extended.max_acceleration);
EXPECT_EQ(-1, joint_limits_extended.max_deceleration);
}

TEST_F(JointLimitTest, readNonExistingJointLimit)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,6 @@ TEST_F(JointLimitsAggregator, LimitsViolationVelocity)

int main(int argc, char** argv)
{
ros::init(argc, argv, "unittest_joint_limits_aggregator");
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

0 comments on commit e7ed187

Please sign in to comment.