Skip to content

Commit f084862

Browse files
christophfroehlichmergify[bot]
authored andcommitted
[tricycle_controller] Use generate_parameter_library (#957)
(cherry picked from commit 8d732f1) # Conflicts: # tricycle_controller/test/test_tricycle_controller.cpp
1 parent ad6f25e commit f084862

File tree

8 files changed

+297
-162
lines changed

8 files changed

+297
-162
lines changed

tricycle_controller/CMakeLists.txt

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1010
builtin_interfaces
1111
controller_interface
1212
geometry_msgs
13+
generate_parameter_library
1314
hardware_interface
1415
nav_msgs
1516
pluginlib
@@ -28,6 +29,10 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2829
find_package(${Dependency} REQUIRED)
2930
endforeach()
3031

32+
generate_parameter_library(tricycle_controller_parameters
33+
src/tricycle_controller_parameter.yaml
34+
)
35+
3136
add_library(tricycle_controller SHARED
3237
src/tricycle_controller.cpp
3338
src/odometry.cpp
@@ -39,6 +44,7 @@ target_include_directories(tricycle_controller PUBLIC
3944
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
4045
$<INSTALL_INTERFACE:include/tricycle_controller>
4146
)
47+
target_link_libraries(tricycle_controller PUBLIC tricycle_controller_parameters)
4248
ament_target_dependencies(tricycle_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
4349

4450
pluginlib_export_plugin_description_file(controller_interface tricycle_controller.xml)
@@ -49,8 +55,7 @@ if(BUILD_TESTING)
4955
find_package(ros2_control_test_assets REQUIRED)
5056

5157
ament_add_gmock(test_tricycle_controller
52-
test/test_tricycle_controller.cpp
53-
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml)
58+
test/test_tricycle_controller.cpp)
5459
target_link_libraries(test_tricycle_controller
5560
tricycle_controller
5661
)
@@ -65,8 +70,9 @@ if(BUILD_TESTING)
6570
tf2_msgs
6671
)
6772

68-
ament_add_gmock(test_load_tricycle_controller
73+
add_rostest_with_parameters_gmock(test_load_tricycle_controller
6974
test/test_load_tricycle_controller.cpp
75+
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml
7076
)
7177
target_link_libraries(test_load_tricycle_controller
7278
tricycle_controller
@@ -84,6 +90,7 @@ install(
8490
install(
8591
TARGETS
8692
tricycle_controller
93+
tricycle_controller_parameters
8794
EXPORT export_tricycle_controller
8895
RUNTIME DESTINATION bin
8996
ARCHIVE DESTINATION lib

tricycle_controller/doc/userdoc.rst

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,8 @@
55
tricycle_controller
66
=====================
77

8-
Controller for mobile robots with tricycle drive.
8+
Controller for mobile robots with a single double-actuated wheel, including traction and steering. An example is a tricycle robot with the actuated wheel in the front and two trailing wheels on the rear axle.
9+
910
Input for control are robot base_link twist commands which are translated to traction and steering
1011
commands for the tricycle drive base. Odometry is computed from hardware feedback and published.
1112

@@ -24,3 +25,10 @@ Other features
2425
Odometry publishing
2526
Velocity, acceleration and jerk limits
2627
Automatic stop after command timeout
28+
29+
Parameters
30+
--------------
31+
32+
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.
33+
34+
.. generate_parameter_library_details:: ../src/tricycle_controller_parameter.yaml

tricycle_controller/include/tricycle_controller/tricycle_controller.hpp

Lines changed: 6 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,9 @@
4545
#include "tricycle_controller/traction_limiter.hpp"
4646
#include "tricycle_controller/visibility_control.h"
4747

48+
// auto-generated by generate_parameter_library
49+
#include "tricycle_controller_parameters.hpp"
50+
4851
namespace tricycle_controller
4952
{
5053
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
@@ -109,31 +112,14 @@ class TricycleController : public controller_interface::ControllerInterface
109112
double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase);
110113
std::tuple<double, double> twist_to_ackermann(double linear_command, double angular_command);
111114

112-
std::string traction_joint_name_;
113-
std::string steering_joint_name_;
115+
// Parameters from ROS for tricycle_controller
116+
std::shared_ptr<ParamListener> param_listener_;
117+
Params params_;
114118

115119
// HACK: put into vector to avoid initializing structs because they have no default constructors
116120
std::vector<TractionHandle> traction_joint_;
117121
std::vector<SteeringHandle> steering_joint_;
118122

119-
struct WheelParams
120-
{
121-
double wheelbase = 0.0;
122-
double radius = 0.0;
123-
} wheel_params_;
124-
125-
struct OdometryParams
126-
{
127-
bool open_loop = false;
128-
bool enable_odom_tf = false;
129-
bool odom_only_twist = false; // for doing the pose integration in separate node
130-
std::string base_frame_id = "base_link";
131-
std::string odom_frame_id = "odom";
132-
std::array<double, 6> pose_covariance_diagonal;
133-
std::array<double, 6> twist_covariance_diagonal;
134-
} odom_params_;
135-
136-
bool publish_ackermann_command_ = false;
137123
std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ = nullptr;
138124
std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
139125
realtime_ackermann_command_publisher_ = nullptr;
@@ -168,7 +154,6 @@ class TricycleController : public controller_interface::ControllerInterface
168154
SteeringLimiter limiter_steering_;
169155

170156
bool is_halted = false;
171-
bool use_stamped_vel_ = true;
172157

173158
void reset_odometry(
174159
const std::shared_ptr<rmw_request_id_t> request_header,

tricycle_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
<author email="[email protected]">Tony Najjar</author>
1111

1212
<buildtool_depend>ament_cmake</buildtool_depend>
13+
<build_depend>generate_parameter_library</build_depend>
1314

1415
<depend>ackermann_msgs</depend>
1516
<depend>backward_ros</depend>

0 commit comments

Comments
 (0)