diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index c4ba9a71cd..3156d0d80f 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -335,6 +335,10 @@ controller_interface::CallbackReturn DiffDriveController::on_configure( cmd_vel_timeout_ = rclcpp::Duration::from_seconds(params_.cmd_vel_timeout); publish_limited_velocity_ = params_.publish_limited_velocity; + // Allocate reference interfaces if needed + const int nr_ref_itfs = 2; + reference_interfaces_.resize(nr_ref_itfs, std::numeric_limits::quiet_NaN()); + // TODO(christophfroehlich) remove deprecated parameters // START DEPRECATED if (!params_.linear.x.has_velocity_limits) @@ -716,10 +720,8 @@ bool DiffDriveController::on_set_chained_mode(bool chained_mode) std::vector DiffDriveController::on_export_reference_interfaces() { - const int nr_ref_itfs = 2; - reference_interfaces_.resize(nr_ref_itfs, std::numeric_limits::quiet_NaN()); std::vector reference_interfaces; - reference_interfaces.reserve(nr_ref_itfs); + reference_interfaces.reserve(reference_interfaces_.size()); reference_interfaces.push_back(hardware_interface::CommandInterface( get_node()->get_name(), std::string("linear/") + hardware_interface::HW_IF_VELOCITY,