Skip to content

Commit 2bf3093

Browse files
authored
Remove unnecessary publish_limited_velocity_ member (#2266)
1 parent fc570f8 commit 2bf3093

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
@@ -141,7 +141,6 @@ class DiffDriveController : public controller_interface::ChainableControllerInte
141141
std::unique_ptr<SpeedLimiter> limiter_linear_;
142142
std::unique_ptr<SpeedLimiter> limiter_angular_;
143143

144-
bool publish_limited_velocity_ = false;
145144
std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ = nullptr;
146145
std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
147146
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
@@ -300,7 +300,7 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
300300
previous_two_commands_.push({{linear_command, angular_command}});
301301

302302
// Publish limited velocity
303-
if (publish_limited_velocity_ && realtime_limited_velocity_publisher_)
303+
if (params_.publish_limited_velocity && realtime_limited_velocity_publisher_)
304304
{
305305
limited_velocity_message_.header.stamp = time;
306306
limited_velocity_message_.twist.linear.x = linear_command;
@@ -361,7 +361,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
361361
odometry_.setVelocityRollingWindowSize(static_cast<size_t>(params_.velocity_rolling_window_size));
362362

363363
cmd_vel_timeout_ = rclcpp::Duration::from_seconds(params_.cmd_vel_timeout);
364-
publish_limited_velocity_ = params_.publish_limited_velocity;
365364

366365
// Allocate reference interfaces if needed
367366
const int nr_ref_itfs = 2;
@@ -387,7 +386,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
387386
// left and right sides are both equal at this point
388387
wheels_per_side_ = static_cast<int>(params_.left_wheel_names.size());
389388

390-
if (publish_limited_velocity_)
389+
if (params_.publish_limited_velocity)
391390
{
392391
limited_velocity_publisher_ = get_node()->create_publisher<TwistStamped>(
393392
DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS());

0 commit comments

Comments
 (0)