File tree Expand file tree Collapse file tree
Expand file tree Collapse file tree Original file line number Diff line number Diff line change @@ -260,6 +260,7 @@ bool PidROS::initialize_from_ros_parameters()
260260 u_max = UMAX_INFINITY;
261261 u_min = -UMAX_INFINITY;
262262 bool antiwindup = false ;
263+ bool saturation = false ;
263264 std::string antiwindup_strat_str = " legacy" ;
264265 bool all_params_available = true ;
265266
@@ -274,9 +275,17 @@ bool PidROS::initialize_from_ros_parameters()
274275 all_params_available &=
275276 get_double_param (param_prefix_ + " tracking_time_constant" , tracking_time_constant);
276277
278+ get_boolean_param (param_prefix_ + " saturation" , saturation);
279+ if (!saturation)
280+ {
281+ u_max = UMAX_INFINITY;
282+ u_min = -UMAX_INFINITY;
283+ }
277284 get_boolean_param (param_prefix_ + " antiwindup" , antiwindup);
278285 get_string_param (param_prefix_ + " antiwindup_strategy" , antiwindup_strat_str);
279286 declare_param (param_prefix_ + " save_i_term" , rclcpp::ParameterValue (false ));
287+ declare_param (
288+ param_prefix_ + " activate_state_publisher" , rclcpp::ParameterValue (rt_state_pub_ != nullptr ));
280289
281290 if (all_params_available)
282291 {
You can’t perform that action at this time.
0 commit comments