@@ -834,12 +834,12 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
834
834
rcl_interfaces::msg::SetParametersResult result;
835
835
836
836
for (auto parameter : parameters) {
837
- const auto & type = parameter.get_type ();
838
- const auto & name = parameter.get_name ();
837
+ const auto & param_type = parameter.get_type ();
838
+ const auto & param_name = parameter.get_name ();
839
839
840
840
// If we are trying to change the parameter of a plugin we can just skip it at this point
841
841
// as they handle parameter changes themselves and don't need to lock the mutex
842
- if (name .find (' .' ) != std::string::npos) {
842
+ if (param_name .find (' .' ) != std::string::npos) {
843
843
continue ;
844
844
}
845
845
@@ -853,16 +853,14 @@ ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
853
853
return result;
854
854
}
855
855
856
- if (type == ParameterType::PARAMETER_DOUBLE) {
857
- if (name == " controller_frequency" ) {
858
- controller_frequency_ = parameter.as_double ();
859
- } else if (name == " min_x_velocity_threshold" ) {
856
+ if (param_type == ParameterType::PARAMETER_DOUBLE) {
857
+ if (param_name == " min_x_velocity_threshold" ) {
860
858
min_x_velocity_threshold_ = parameter.as_double ();
861
- } else if (name == " min_y_velocity_threshold" ) {
859
+ } else if (param_name == " min_y_velocity_threshold" ) {
862
860
min_y_velocity_threshold_ = parameter.as_double ();
863
- } else if (name == " min_theta_velocity_threshold" ) {
861
+ } else if (param_name == " min_theta_velocity_threshold" ) {
864
862
min_theta_velocity_threshold_ = parameter.as_double ();
865
- } else if (name == " failure_tolerance" ) {
863
+ } else if (param_name == " failure_tolerance" ) {
866
864
failure_tolerance_ = parameter.as_double ();
867
865
}
868
866
}
0 commit comments