Skip to content

Commit 6adb847

Browse files
[backport] Fix #730 (#736)
* Fix file name for include guard (backport #681) (cherry picked from commit c619aac) Co-authored-by: Christoph Fröhlich <[email protected]> * Activate AdmittanceControllerTestParameterizedInvalidParameters (#711) (#733) * [JTC] Re-enabling test, bugfixing and hardening. Adding a parameter to define when trajectories with non-zero velocity at the end are used. (backport #705) (#706) * Enable effort rejection test --------- Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
1 parent 17e14e3 commit 6adb847

15 files changed

+552
-1050
lines changed

.github/workflows/rolling-binary-build-main.yml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,13 @@ on:
66
workflow_dispatch:
77
branches:
88
- master
9+
- '*feature*'
10+
- '*feature/**'
911
pull_request:
1012
branches:
1113
- master
14+
- '*feature*'
15+
- '*feature/**'
1216
push:
1317
branches:
1418
- master

.github/workflows/rolling-binary-build-testing.yml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,13 @@ on:
66
workflow_dispatch:
77
branches:
88
- master
9+
- '*feature*'
10+
- '*feature/**'
911
pull_request:
1012
branches:
1113
- master
14+
- '*feature*'
15+
- '*feature/**'
1216
push:
1317
branches:
1418
- master

.github/workflows/rolling-semi-binary-build-main.yml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,13 @@ on:
55
workflow_dispatch:
66
branches:
77
- master
8+
- '*feature*'
9+
- '*feature/**'
810
pull_request:
911
branches:
1012
- master
13+
- '*feature*'
14+
- '*feature/**'
1115
push:
1216
branches:
1317
- master

.github/workflows/rolling-semi-binary-build-testing.yml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,13 @@ on:
55
workflow_dispatch:
66
branches:
77
- master
8+
- '*feature*'
9+
- '*feature/**'
810
pull_request:
911
branches:
1012
- master
13+
- '*feature*'
14+
- '*feature/**'
1115
push:
1216
branches:
1317
- master

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,10 +67,18 @@ INSTANTIATE_TEST_SUITE_P(
6767
// wrong length selected axes
6868
std::make_tuple(
6969
std::string("admittance.selected_axes"),
70-
rclcpp::ParameterValue(std::vector<double>() = {1, 2, 3})),
71-
// invalid robot description
72-
std::make_tuple(
73-
std::string("robot_description"), rclcpp::ParameterValue(std::string() = "bad_robot"))));
70+
rclcpp::ParameterValue(std::vector<double>() = {1, 2, 3}))
71+
// invalid robot description.
72+
// TODO(anyone): deactivated, because SetUpController returns SUCCESS here?
73+
// ,std::make_tuple(
74+
// std::string("robot_description"), rclcpp::ParameterValue(std::string() = "bad_robot")))
75+
));
76+
77+
// Test on_init returns ERROR when a parameter is invalid
78+
TEST_P(AdmittanceControllerTestParameterizedInvalidParameters, invalid_parameters)
79+
{
80+
ASSERT_EQ(SetUpController(), controller_interface::return_type::ERROR);
81+
}
7482

7583
TEST_F(AdmittanceControllerTest, all_parameters_set_configure_success)
7684
{

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,6 @@
2727

2828
#include "gmock/gmock.h"
2929

30-
#include "6d_robot_description.hpp"
3130
#include "admittance_controller/admittance_controller.hpp"
3231
#include "control_msgs/msg/admittance_controller_state.hpp"
3332
#include "geometry_msgs/msg/transform_stamped.hpp"
@@ -38,6 +37,7 @@
3837
#include "rclcpp/utilities.hpp"
3938
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
4039
#include "semantic_components/force_torque_sensor.hpp"
40+
#include "test_asset_6d_robot_description.hpp"
4141
#include "tf2_ros/transform_broadcaster.h"
4242
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4343

@@ -454,9 +454,15 @@ class AdmittanceControllerTestParameterizedInvalidParameters
454454
static void TearDownTestCase() { AdmittanceControllerTest::TearDownTestCase(); }
455455

456456
protected:
457-
void SetUpController()
457+
controller_interface::return_type SetUpController()
458458
{
459-
AdmittanceControllerTest::SetUpController("test_admittance_controller");
459+
auto param_name = std::get<0>(GetParam());
460+
auto param_value = std::get<1>(GetParam());
461+
std::vector<rclcpp::Parameter> parameter_overrides;
462+
rclcpp::Parameter param(param_name, param_value);
463+
parameter_overrides.push_back(param);
464+
return AdmittanceControllerTest::SetUpController(
465+
"test_admittance_controller", parameter_overrides);
460466
}
461467
};
462468

admittance_controller/test/6d_robot_description.hpp renamed to admittance_controller/test/test_asset_6d_robot_description.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef ROS2_CONTROL_TEST_ASSETS__6D_ROBOT_DESCRIPTION_HPP_
16-
#define ROS2_CONTROL_TEST_ASSETS__6D_ROBOT_DESCRIPTION_HPP_
15+
#ifndef TEST_ASSET_6D_ROBOT_DESCRIPTION_HPP_
16+
#define TEST_ASSET_6D_ROBOT_DESCRIPTION_HPP_
1717

1818
#include <string>
1919

@@ -310,4 +310,4 @@ const auto valid_6d_robot_srdf =
310310

311311
} // namespace ros2_control_test_assets
312312

313-
#endif // ROS2_CONTROL_TEST_ASSETS__6D_ROBOT_DESCRIPTION_HPP_
313+
#endif // TEST_ASSET_6D_ROBOT_DESCRIPTION_HPP_

joint_trajectory_controller/CMakeLists.txt

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -78,13 +78,13 @@ if(BUILD_TESTING)
7878
ros2_control_test_assets
7979
)
8080

81-
# TODO(andyz): Disabled due to flakiness
82-
# ament_add_gmock(test_trajectory_actions
83-
# test/test_trajectory_actions.cpp
84-
# )
85-
# target_link_libraries(test_trajectory_actions
86-
# joint_trajectory_controller
87-
# )
81+
ament_add_gmock(test_trajectory_actions
82+
test/test_trajectory_actions.cpp
83+
)
84+
set_tests_properties(test_trajectory_actions PROPERTIES TIMEOUT 300)
85+
target_link_libraries(test_trajectory_actions
86+
joint_trajectory_controller
87+
)
8888
endif()
8989

9090

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -159,6 +159,11 @@ open_loop_control (boolean)
159159

160160
If this flag is set, the controller tries to read the values from the command interfaces on starting. If they have real numeric values, those will be used instead of state interfaces. Therefore it is important set command interfaces to NaN (std::numeric_limits<double>::quiet_NaN()) or state values when the hardware is started.
161161

162+
allow_nonzero_velocity_at_trajectory_end (boolean)
163+
If false, the last velocity point has to be zero or the goal will be rejected.
164+
165+
Default: true
166+
162167
constraints (structure)
163168
Default values for tolerances if no explicit values are states in JointTrajectory message.
164169

joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,11 @@
1919
#include <vector>
2020

2121
#include "parameter_traits/parameter_traits.hpp"
22+
#include "rclcpp/parameter.hpp"
2223
#include "rsl/algorithm.hpp"
2324
#include "tl_expected/expected.hpp"
2425

25-
namespace parameter_traits
26+
namespace joint_trajectory_controller
2627
{
2728
tl::expected<void, std::string> command_interface_type_combinations(
2829
rclcpp::Parameter const & parameter)
@@ -94,6 +95,6 @@ tl::expected<void, std::string> state_interface_type_combinations(
9495
return {};
9596
}
9697

97-
} // namespace parameter_traits
98+
} // namespace joint_trajectory_controller
9899

99100
#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_

0 commit comments

Comments
 (0)