Skip to content

Commit dbe2658

Browse files
[tricycle_controller] Use generate_parameter_library (#957)
(cherry picked from commit 8d732f1) # Conflicts: # tricycle_controller/src/tricycle_controller.cpp # tricycle_controller/test/test_tricycle_controller.cpp
1 parent 468e030 commit dbe2658

File tree

8 files changed

+300
-127
lines changed

8 files changed

+300
-127
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
target_compile_definitions(tricycle_controller PRIVATE _USE_MATH_DEFINES)
4450

@@ -50,8 +56,7 @@ if(BUILD_TESTING)
5056
find_package(ros2_control_test_assets REQUIRED)
5157

5258
ament_add_gmock(test_tricycle_controller
53-
test/test_tricycle_controller.cpp
54-
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml)
59+
test/test_tricycle_controller.cpp)
5560
target_link_libraries(test_tricycle_controller
5661
tricycle_controller
5762
)
@@ -66,8 +71,9 @@ if(BUILD_TESTING)
6671
tf2_msgs
6772
)
6873

69-
ament_add_gmock(test_load_tricycle_controller
74+
add_rostest_with_parameters_gmock(test_load_tricycle_controller
7075
test/test_load_tricycle_controller.cpp
76+
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_tricycle_controller.yaml
7177
)
7278
target_link_libraries(test_load_tricycle_controller
7379
tricycle_controller
@@ -85,6 +91,7 @@ install(
8591
install(
8692
TARGETS
8793
tricycle_controller
94+
tricycle_controller_parameters
8895
EXPORT export_tricycle_controller
8996
RUNTIME DESTINATION bin
9097
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>

tricycle_controller/src/tricycle_controller.cpp

Lines changed: 45 additions & 74 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ CallbackReturn TricycleController::on_init()
5252
{
5353
try
5454
{
55+
<<<<<<< HEAD
5556
// with the lifecycle node being initialized, we can declare parameters
5657
auto_declare<std::string>("traction_joint_name", std::string());
5758
auto_declare<std::string>("steering_joint_name", std::string());
@@ -87,6 +88,11 @@ CallbackReturn TricycleController::on_init()
8788
auto_declare<double>("steering.min_velocity", NAN);
8889
auto_declare<double>("steering.max_acceleration", NAN);
8990
auto_declare<double>("steering.min_acceleration", NAN);
91+
=======
92+
// Create the parameter listener and get the parameters
93+
param_listener_ = std::make_shared<ParamListener>(get_node());
94+
params_ = param_listener_->get_params();
95+
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))
9096
}
9197
catch (const std::exception & e)
9298
{
@@ -101,17 +107,17 @@ InterfaceConfiguration TricycleController::command_interface_configuration() con
101107
{
102108
InterfaceConfiguration command_interfaces_config;
103109
command_interfaces_config.type = interface_configuration_type::INDIVIDUAL;
104-
command_interfaces_config.names.push_back(traction_joint_name_ + "/" + HW_IF_VELOCITY);
105-
command_interfaces_config.names.push_back(steering_joint_name_ + "/" + HW_IF_POSITION);
110+
command_interfaces_config.names.push_back(params_.traction_joint_name + "/" + HW_IF_VELOCITY);
111+
command_interfaces_config.names.push_back(params_.steering_joint_name + "/" + HW_IF_POSITION);
106112
return command_interfaces_config;
107113
}
108114

109115
InterfaceConfiguration TricycleController::state_interface_configuration() const
110116
{
111117
InterfaceConfiguration state_interfaces_config;
112118
state_interfaces_config.type = interface_configuration_type::INDIVIDUAL;
113-
state_interfaces_config.names.push_back(traction_joint_name_ + "/" + HW_IF_VELOCITY);
114-
state_interfaces_config.names.push_back(steering_joint_name_ + "/" + HW_IF_POSITION);
119+
state_interfaces_config.names.push_back(params_.traction_joint_name + "/" + HW_IF_VELOCITY);
120+
state_interfaces_config.names.push_back(params_.steering_joint_name + "/" + HW_IF_POSITION);
115121
return state_interfaces_config;
116122
}
117123

@@ -151,7 +157,7 @@ controller_interface::return_type TricycleController::update(
151157
double Ws_read = traction_joint_[0].velocity_state.get().get_value(); // in radians/s
152158
double alpha_read = steering_joint_[0].position_state.get().get_value(); // in radians
153159

154-
if (odom_params_.open_loop)
160+
if (params_.open_loop)
155161
{
156162
odometry_.updateOpenLoop(linear_command, angular_command, period);
157163
}
@@ -172,7 +178,7 @@ controller_interface::return_type TricycleController::update(
172178
{
173179
auto & odometry_message = realtime_odometry_publisher_->msg_;
174180
odometry_message.header.stamp = time;
175-
if (!odom_params_.odom_only_twist)
181+
if (!params_.odom_only_twist)
176182
{
177183
odometry_message.pose.pose.position.x = odometry_.getX();
178184
odometry_message.pose.pose.position.y = odometry_.getY();
@@ -186,7 +192,7 @@ controller_interface::return_type TricycleController::update(
186192
realtime_odometry_publisher_->unlockAndPublish();
187193
}
188194

189-
if (odom_params_.enable_odom_tf && realtime_odometry_transform_publisher_->trylock())
195+
if (params_.enable_odom_tf && realtime_odometry_transform_publisher_->trylock())
190196
{
191197
auto & transform = realtime_odometry_transform_publisher_->msg_.transforms.front();
192198
transform.header.stamp = time;
@@ -239,7 +245,7 @@ controller_interface::return_type TricycleController::update(
239245
previous_commands_.emplace(ackermann_command);
240246

241247
// Publish ackermann command
242-
if (publish_ackermann_command_ && realtime_ackermann_command_publisher_->trylock())
248+
if (params_.publish_ackermann_command && realtime_ackermann_command_publisher_->trylock())
243249
{
244250
auto & realtime_ackermann_command = realtime_ackermann_command_publisher_->msg_;
245251
// speed in AckermannDrive is defined desired forward speed (m/s) but we use it here as wheel
@@ -258,74 +264,40 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
258264
{
259265
auto logger = get_node()->get_logger();
260266

261-
// update parameters
262-
traction_joint_name_ = get_node()->get_parameter("traction_joint_name").as_string();
263-
steering_joint_name_ = get_node()->get_parameter("steering_joint_name").as_string();
264-
if (traction_joint_name_.empty())
267+
// update parameters if they have changed
268+
if (param_listener_->is_old(params_))
265269
{
266-
RCLCPP_ERROR(logger, "'traction_joint_name' parameter was empty");
267-
return CallbackReturn::ERROR;
270+
params_ = param_listener_->get_params();
271+
RCLCPP_INFO(logger, "Parameters were updated");
268272
}
269-
if (steering_joint_name_.empty())
270-
{
271-
RCLCPP_ERROR(logger, "'steering_joint_name' parameter was empty");
272-
return CallbackReturn::ERROR;
273-
}
274-
275-
wheel_params_.wheelbase = get_node()->get_parameter("wheelbase").as_double();
276-
wheel_params_.radius = get_node()->get_parameter("wheel_radius").as_double();
277273

278-
odometry_.setWheelParams(wheel_params_.wheelbase, wheel_params_.radius);
279-
odometry_.setVelocityRollingWindowSize(
280-
get_node()->get_parameter("velocity_rolling_window_size").as_int());
274+
odometry_.setWheelParams(params_.wheelbase, params_.wheel_radius);
275+
odometry_.setVelocityRollingWindowSize(params_.velocity_rolling_window_size);
281276

282-
odom_params_.odom_frame_id = get_node()->get_parameter("odom_frame_id").as_string();
283-
odom_params_.base_frame_id = get_node()->get_parameter("base_frame_id").as_string();
284-
285-
auto pose_diagonal = get_node()->get_parameter("pose_covariance_diagonal").as_double_array();
286-
std::copy(
287-
pose_diagonal.begin(), pose_diagonal.end(), odom_params_.pose_covariance_diagonal.begin());
288-
289-
auto twist_diagonal = get_node()->get_parameter("twist_covariance_diagonal").as_double_array();
290-
std::copy(
291-
twist_diagonal.begin(), twist_diagonal.end(), odom_params_.twist_covariance_diagonal.begin());
292-
293-
odom_params_.open_loop = get_node()->get_parameter("open_loop").as_bool();
294-
odom_params_.enable_odom_tf = get_node()->get_parameter("enable_odom_tf").as_bool();
295-
odom_params_.odom_only_twist = get_node()->get_parameter("odom_only_twist").as_bool();
296-
297-
cmd_vel_timeout_ =
298-
std::chrono::milliseconds{get_node()->get_parameter("cmd_vel_timeout").as_int()};
299-
publish_ackermann_command_ = get_node()->get_parameter("publish_ackermann_command").as_bool();
300-
use_stamped_vel_ = get_node()->get_parameter("use_stamped_vel").as_bool();
277+
cmd_vel_timeout_ = std::chrono::milliseconds{params_.cmd_vel_timeout};
278+
params_.publish_ackermann_command =
279+
get_node()->get_parameter("publish_ackermann_command").as_bool();
280+
params_.use_stamped_vel = get_node()->get_parameter("use_stamped_vel").as_bool();
301281

302282
try
303283
{
304284
limiter_traction_ = TractionLimiter(
305-
get_node()->get_parameter("traction.min_velocity").as_double(),
306-
get_node()->get_parameter("traction.max_velocity").as_double(),
307-
get_node()->get_parameter("traction.min_acceleration").as_double(),
308-
get_node()->get_parameter("traction.max_acceleration").as_double(),
309-
get_node()->get_parameter("traction.min_deceleration").as_double(),
310-
get_node()->get_parameter("traction.max_deceleration").as_double(),
311-
get_node()->get_parameter("traction.min_jerk").as_double(),
312-
get_node()->get_parameter("traction.max_jerk").as_double());
285+
params_.traction.min_velocity, params_.traction.max_velocity,
286+
params_.traction.min_acceleration, params_.traction.max_acceleration,
287+
params_.traction.min_deceleration, params_.traction.max_deceleration,
288+
params_.traction.min_jerk, params_.traction.max_jerk);
313289
}
314290
catch (const std::invalid_argument & e)
315291
{
316292
RCLCPP_ERROR(get_node()->get_logger(), "Error configuring traction limiter: %s", e.what());
317293
return CallbackReturn::ERROR;
318294
}
319-
320295
try
321296
{
322297
limiter_steering_ = SteeringLimiter(
323-
get_node()->get_parameter("steering.min_position").as_double(),
324-
get_node()->get_parameter("steering.max_position").as_double(),
325-
get_node()->get_parameter("steering.min_velocity").as_double(),
326-
get_node()->get_parameter("steering.max_velocity").as_double(),
327-
get_node()->get_parameter("steering.min_acceleration").as_double(),
328-
get_node()->get_parameter("steering.max_acceleration").as_double());
298+
params_.steering.min_position, params_.steering.max_position, params_.steering.min_velocity,
299+
params_.steering.max_velocity, params_.steering.min_acceleration,
300+
params_.steering.max_acceleration);
329301
}
330302
catch (const std::invalid_argument & e)
331303
{
@@ -347,7 +319,7 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
347319
previous_commands_.emplace(empty_ackermann_drive);
348320

349321
// initialize ackermann command publisher
350-
if (publish_ackermann_command_)
322+
if (params_.publish_ackermann_command)
351323
{
352324
ackermann_command_publisher_ = get_node()->create_publisher<AckermannDrive>(
353325
DEFAULT_ACKERMANN_OUT_TOPIC, rclcpp::SystemDefaultsQoS());
@@ -357,7 +329,7 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
357329
}
358330

359331
// initialize command subscriber
360-
if (use_stamped_vel_)
332+
if (params_.use_stamped_vel)
361333
{
362334
velocity_command_subscriber_ = get_node()->create_subscription<TwistStamped>(
363335
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(),
@@ -409,8 +381,8 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
409381
odometry_publisher_);
410382

411383
auto & odometry_message = realtime_odometry_publisher_->msg_;
412-
odometry_message.header.frame_id = odom_params_.odom_frame_id;
413-
odometry_message.child_frame_id = odom_params_.base_frame_id;
384+
odometry_message.header.frame_id = params_.odom_frame_id;
385+
odometry_message.child_frame_id = params_.base_frame_id;
414386

415387
// initialize odom values zeros
416388
odometry_message.twist =
@@ -421,13 +393,12 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
421393
{
422394
// 0, 7, 14, 21, 28, 35
423395
const size_t diagonal_index = NUM_DIMENSIONS * index + index;
424-
odometry_message.pose.covariance[diagonal_index] = odom_params_.pose_covariance_diagonal[index];
425-
odometry_message.twist.covariance[diagonal_index] =
426-
odom_params_.twist_covariance_diagonal[index];
396+
odometry_message.pose.covariance[diagonal_index] = params_.pose_covariance_diagonal[index];
397+
odometry_message.twist.covariance[diagonal_index] = params_.twist_covariance_diagonal[index];
427398
}
428399

429400
// initialize transform publisher and message
430-
if (odom_params_.enable_odom_tf)
401+
if (params_.enable_odom_tf)
431402
{
432403
odometry_transform_publisher_ = get_node()->create_publisher<tf2_msgs::msg::TFMessage>(
433404
DEFAULT_TRANSFORM_TOPIC, rclcpp::SystemDefaultsQoS());
@@ -438,8 +409,8 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
438409
// keeping track of odom and base_link transforms only
439410
auto & odometry_transform_message = realtime_odometry_transform_publisher_->msg_;
440411
odometry_transform_message.transforms.resize(1);
441-
odometry_transform_message.transforms.front().header.frame_id = odom_params_.odom_frame_id;
442-
odometry_transform_message.transforms.front().child_frame_id = odom_params_.base_frame_id;
412+
odometry_transform_message.transforms.front().header.frame_id = params_.odom_frame_id;
413+
odometry_transform_message.transforms.front().child_frame_id = params_.base_frame_id;
443414
}
444415

445416
// Create odom reset service
@@ -456,8 +427,8 @@ CallbackReturn TricycleController::on_activate(const rclcpp_lifecycle::State &)
456427
RCLCPP_INFO(get_node()->get_logger(), "On activate: Initialize Joints");
457428

458429
// Initialize the joints
459-
const auto wheel_front_result = get_traction(traction_joint_name_, traction_joint_);
460-
const auto steering_result = get_steering(steering_joint_name_, steering_joint_);
430+
const auto wheel_front_result = get_traction(params_.traction_joint_name, traction_joint_);
431+
const auto steering_result = get_steering(params_.steering_joint_name, steering_joint_);
461432
if (wheel_front_result == CallbackReturn::ERROR || steering_result == CallbackReturn::ERROR)
462433
{
463434
return CallbackReturn::ERROR;
@@ -644,12 +615,12 @@ std::tuple<double, double> TricycleController::twist_to_ackermann(double Vx, dou
644615
if (Vx == 0 && theta_dot != 0)
645616
{ // is spin action
646617
alpha = theta_dot > 0 ? M_PI_2 : -M_PI_2;
647-
Ws = abs(theta_dot) * wheel_params_.wheelbase / wheel_params_.radius;
618+
Ws = abs(theta_dot) * params_.wheelbase / params_.wheel_radius;
648619
return std::make_tuple(alpha, Ws);
649620
}
650621

651-
alpha = convert_trans_rot_vel_to_steering_angle(Vx, theta_dot, wheel_params_.wheelbase);
652-
Ws = Vx / (wheel_params_.radius * std::cos(alpha));
622+
alpha = convert_trans_rot_vel_to_steering_angle(Vx, theta_dot, params_.wheelbase);
623+
Ws = Vx / (params_.wheel_radius * std::cos(alpha));
653624
return std::make_tuple(alpha, Ws);
654625
}
655626

0 commit comments

Comments
 (0)