Skip to content

Commit 28ede2c

Browse files
authored
Remove unnecessary publish_limited_velocity_ member (backport #2266) (#2268)
1 parent 38cb9af commit 28ede2c

File tree

2 files changed

+2
-4
lines changed

2 files changed

+2
-4
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,6 @@ class DiffDriveController : public controller_interface::ChainableControllerInte
134134
std::unique_ptr<SpeedLimiter> limiter_linear_;
135135
std::unique_ptr<SpeedLimiter> limiter_angular_;
136136

137-
bool publish_limited_velocity_ = false;
138137
std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ = nullptr;
139138
std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
140139
realtime_limited_velocity_publisher_ = nullptr;

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -270,7 +270,7 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
270270
previous_two_commands_.push({{linear_command, angular_command}});
271271

272272
// Publish limited velocity
273-
if (publish_limited_velocity_ && realtime_limited_velocity_publisher_)
273+
if (params_.publish_limited_velocity && realtime_limited_velocity_publisher_)
274274
{
275275
limited_velocity_message_.header.stamp = time;
276276
limited_velocity_message_.twist.linear.x = linear_command;
@@ -332,7 +332,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
332332
odometry_.setVelocityRollingWindowSize(static_cast<size_t>(params_.velocity_rolling_window_size));
333333

334334
cmd_vel_timeout_ = rclcpp::Duration::from_seconds(params_.cmd_vel_timeout);
335-
publish_limited_velocity_ = params_.publish_limited_velocity;
336335

337336
// Allocate reference interfaces if needed
338337
const int nr_ref_itfs = 2;
@@ -419,7 +418,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
419418
// left and right sides are both equal at this point
420419
wheels_per_side_ = static_cast<int>(params_.left_wheel_names.size());
421420

422-
if (publish_limited_velocity_)
421+
if (params_.publish_limited_velocity)
423422
{
424423
limited_velocity_publisher_ = get_node()->create_publisher<TwistStamped>(
425424
DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS());

0 commit comments

Comments
 (0)