@@ -52,6 +52,7 @@ CallbackReturn TricycleController::on_init()
5252{
5353 try
5454 {
55+ <<<<<<< HEAD
5556 // with the lifecycle node being initialized, we can declare parameters
5657 auto_declare<std::string>(" traction_joint_name" , std::string ());
5758 auto_declare<std::string>(" steering_joint_name" , std::string ());
@@ -87,6 +88,11 @@ CallbackReturn TricycleController::on_init()
8788 auto_declare<double >(" steering.min_velocity" , NAN);
8889 auto_declare<double >(" steering.max_acceleration" , NAN);
8990 auto_declare<double >(" steering.min_acceleration" , NAN);
91+ =======
92+ // Create the parameter listener and get the parameters
93+ param_listener_ = std::make_shared<ParamListener>(get_node ());
94+ params_ = param_listener_->get_params ();
95+ >>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957 ))
9096 }
9197 catch (const std::exception & e)
9298 {
@@ -101,17 +107,17 @@ InterfaceConfiguration TricycleController::command_interface_configuration() con
101107{
102108 InterfaceConfiguration command_interfaces_config;
103109 command_interfaces_config.type = interface_configuration_type::INDIVIDUAL;
104- command_interfaces_config.names .push_back (traction_joint_name_ + " /" + HW_IF_VELOCITY);
105- command_interfaces_config.names .push_back (steering_joint_name_ + " /" + HW_IF_POSITION);
110+ command_interfaces_config.names .push_back (params_. traction_joint_name + " /" + HW_IF_VELOCITY);
111+ command_interfaces_config.names .push_back (params_. steering_joint_name + " /" + HW_IF_POSITION);
106112 return command_interfaces_config;
107113}
108114
109115InterfaceConfiguration TricycleController::state_interface_configuration () const
110116{
111117 InterfaceConfiguration state_interfaces_config;
112118 state_interfaces_config.type = interface_configuration_type::INDIVIDUAL;
113- state_interfaces_config.names .push_back (traction_joint_name_ + " /" + HW_IF_VELOCITY);
114- state_interfaces_config.names .push_back (steering_joint_name_ + " /" + HW_IF_POSITION);
119+ state_interfaces_config.names .push_back (params_. traction_joint_name + " /" + HW_IF_VELOCITY);
120+ state_interfaces_config.names .push_back (params_. steering_joint_name + " /" + HW_IF_POSITION);
115121 return state_interfaces_config;
116122}
117123
@@ -151,7 +157,7 @@ controller_interface::return_type TricycleController::update(
151157 double Ws_read = traction_joint_[0 ].velocity_state .get ().get_value (); // in radians/s
152158 double alpha_read = steering_joint_[0 ].position_state .get ().get_value (); // in radians
153159
154- if (odom_params_ .open_loop )
160+ if (params_ .open_loop )
155161 {
156162 odometry_.updateOpenLoop (linear_command, angular_command, period);
157163 }
@@ -172,7 +178,7 @@ controller_interface::return_type TricycleController::update(
172178 {
173179 auto & odometry_message = realtime_odometry_publisher_->msg_ ;
174180 odometry_message.header .stamp = time;
175- if (!odom_params_ .odom_only_twist )
181+ if (!params_ .odom_only_twist )
176182 {
177183 odometry_message.pose .pose .position .x = odometry_.getX ();
178184 odometry_message.pose .pose .position .y = odometry_.getY ();
@@ -186,7 +192,7 @@ controller_interface::return_type TricycleController::update(
186192 realtime_odometry_publisher_->unlockAndPublish ();
187193 }
188194
189- if (odom_params_ .enable_odom_tf && realtime_odometry_transform_publisher_->trylock ())
195+ if (params_ .enable_odom_tf && realtime_odometry_transform_publisher_->trylock ())
190196 {
191197 auto & transform = realtime_odometry_transform_publisher_->msg_ .transforms .front ();
192198 transform.header .stamp = time;
@@ -239,7 +245,7 @@ controller_interface::return_type TricycleController::update(
239245 previous_commands_.emplace (ackermann_command);
240246
241247 // Publish ackermann command
242- if (publish_ackermann_command_ && realtime_ackermann_command_publisher_->trylock ())
248+ if (params_. publish_ackermann_command && realtime_ackermann_command_publisher_->trylock ())
243249 {
244250 auto & realtime_ackermann_command = realtime_ackermann_command_publisher_->msg_ ;
245251 // speed in AckermannDrive is defined desired forward speed (m/s) but we use it here as wheel
@@ -258,74 +264,40 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
258264{
259265 auto logger = get_node ()->get_logger ();
260266
261- // update parameters
262- traction_joint_name_ = get_node ()->get_parameter (" traction_joint_name" ).as_string ();
263- steering_joint_name_ = get_node ()->get_parameter (" steering_joint_name" ).as_string ();
264- if (traction_joint_name_.empty ())
267+ // update parameters if they have changed
268+ if (param_listener_->is_old (params_))
265269 {
266- RCLCPP_ERROR (logger, " 'traction_joint_name' parameter was empty " );
267- return CallbackReturn::ERROR ;
270+ params_ = param_listener_-> get_params ( );
271+ RCLCPP_INFO (logger, " Parameters were updated " ) ;
268272 }
269- if (steering_joint_name_.empty ())
270- {
271- RCLCPP_ERROR (logger, " 'steering_joint_name' parameter was empty" );
272- return CallbackReturn::ERROR;
273- }
274-
275- wheel_params_.wheelbase = get_node ()->get_parameter (" wheelbase" ).as_double ();
276- wheel_params_.radius = get_node ()->get_parameter (" wheel_radius" ).as_double ();
277273
278- odometry_.setWheelParams (wheel_params_.wheelbase , wheel_params_.radius );
279- odometry_.setVelocityRollingWindowSize (
280- get_node ()->get_parameter (" velocity_rolling_window_size" ).as_int ());
274+ odometry_.setWheelParams (params_.wheelbase , params_.wheel_radius );
275+ odometry_.setVelocityRollingWindowSize (params_.velocity_rolling_window_size );
281276
282- odom_params_.odom_frame_id = get_node ()->get_parameter (" odom_frame_id" ).as_string ();
283- odom_params_.base_frame_id = get_node ()->get_parameter (" base_frame_id" ).as_string ();
284-
285- auto pose_diagonal = get_node ()->get_parameter (" pose_covariance_diagonal" ).as_double_array ();
286- std::copy (
287- pose_diagonal.begin (), pose_diagonal.end (), odom_params_.pose_covariance_diagonal .begin ());
288-
289- auto twist_diagonal = get_node ()->get_parameter (" twist_covariance_diagonal" ).as_double_array ();
290- std::copy (
291- twist_diagonal.begin (), twist_diagonal.end (), odom_params_.twist_covariance_diagonal .begin ());
292-
293- odom_params_.open_loop = get_node ()->get_parameter (" open_loop" ).as_bool ();
294- odom_params_.enable_odom_tf = get_node ()->get_parameter (" enable_odom_tf" ).as_bool ();
295- odom_params_.odom_only_twist = get_node ()->get_parameter (" odom_only_twist" ).as_bool ();
296-
297- cmd_vel_timeout_ =
298- std::chrono::milliseconds{get_node ()->get_parameter (" cmd_vel_timeout" ).as_int ()};
299- publish_ackermann_command_ = get_node ()->get_parameter (" publish_ackermann_command" ).as_bool ();
300- use_stamped_vel_ = get_node ()->get_parameter (" use_stamped_vel" ).as_bool ();
277+ cmd_vel_timeout_ = std::chrono::milliseconds{params_.cmd_vel_timeout };
278+ params_.publish_ackermann_command =
279+ get_node ()->get_parameter (" publish_ackermann_command" ).as_bool ();
280+ params_.use_stamped_vel = get_node ()->get_parameter (" use_stamped_vel" ).as_bool ();
301281
302282 try
303283 {
304284 limiter_traction_ = TractionLimiter (
305- get_node ()->get_parameter (" traction.min_velocity" ).as_double (),
306- get_node ()->get_parameter (" traction.max_velocity" ).as_double (),
307- get_node ()->get_parameter (" traction.min_acceleration" ).as_double (),
308- get_node ()->get_parameter (" traction.max_acceleration" ).as_double (),
309- get_node ()->get_parameter (" traction.min_deceleration" ).as_double (),
310- get_node ()->get_parameter (" traction.max_deceleration" ).as_double (),
311- get_node ()->get_parameter (" traction.min_jerk" ).as_double (),
312- get_node ()->get_parameter (" traction.max_jerk" ).as_double ());
285+ params_.traction .min_velocity , params_.traction .max_velocity ,
286+ params_.traction .min_acceleration , params_.traction .max_acceleration ,
287+ params_.traction .min_deceleration , params_.traction .max_deceleration ,
288+ params_.traction .min_jerk , params_.traction .max_jerk );
313289 }
314290 catch (const std::invalid_argument & e)
315291 {
316292 RCLCPP_ERROR (get_node ()->get_logger (), " Error configuring traction limiter: %s" , e.what ());
317293 return CallbackReturn::ERROR;
318294 }
319-
320295 try
321296 {
322297 limiter_steering_ = SteeringLimiter (
323- get_node ()->get_parameter (" steering.min_position" ).as_double (),
324- get_node ()->get_parameter (" steering.max_position" ).as_double (),
325- get_node ()->get_parameter (" steering.min_velocity" ).as_double (),
326- get_node ()->get_parameter (" steering.max_velocity" ).as_double (),
327- get_node ()->get_parameter (" steering.min_acceleration" ).as_double (),
328- get_node ()->get_parameter (" steering.max_acceleration" ).as_double ());
298+ params_.steering .min_position , params_.steering .max_position , params_.steering .min_velocity ,
299+ params_.steering .max_velocity , params_.steering .min_acceleration ,
300+ params_.steering .max_acceleration );
329301 }
330302 catch (const std::invalid_argument & e)
331303 {
@@ -347,7 +319,7 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
347319 previous_commands_.emplace (empty_ackermann_drive);
348320
349321 // initialize ackermann command publisher
350- if (publish_ackermann_command_ )
322+ if (params_. publish_ackermann_command )
351323 {
352324 ackermann_command_publisher_ = get_node ()->create_publisher <AckermannDrive>(
353325 DEFAULT_ACKERMANN_OUT_TOPIC, rclcpp::SystemDefaultsQoS ());
@@ -357,7 +329,7 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
357329 }
358330
359331 // initialize command subscriber
360- if (use_stamped_vel_ )
332+ if (params_. use_stamped_vel )
361333 {
362334 velocity_command_subscriber_ = get_node ()->create_subscription <TwistStamped>(
363335 DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS (),
@@ -409,8 +381,8 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
409381 odometry_publisher_);
410382
411383 auto & odometry_message = realtime_odometry_publisher_->msg_ ;
412- odometry_message.header .frame_id = odom_params_ .odom_frame_id ;
413- odometry_message.child_frame_id = odom_params_ .base_frame_id ;
384+ odometry_message.header .frame_id = params_ .odom_frame_id ;
385+ odometry_message.child_frame_id = params_ .base_frame_id ;
414386
415387 // initialize odom values zeros
416388 odometry_message.twist =
@@ -421,13 +393,12 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
421393 {
422394 // 0, 7, 14, 21, 28, 35
423395 const size_t diagonal_index = NUM_DIMENSIONS * index + index;
424- odometry_message.pose .covariance [diagonal_index] = odom_params_.pose_covariance_diagonal [index];
425- odometry_message.twist .covariance [diagonal_index] =
426- odom_params_.twist_covariance_diagonal [index];
396+ odometry_message.pose .covariance [diagonal_index] = params_.pose_covariance_diagonal [index];
397+ odometry_message.twist .covariance [diagonal_index] = params_.twist_covariance_diagonal [index];
427398 }
428399
429400 // initialize transform publisher and message
430- if (odom_params_ .enable_odom_tf )
401+ if (params_ .enable_odom_tf )
431402 {
432403 odometry_transform_publisher_ = get_node ()->create_publisher <tf2_msgs::msg::TFMessage>(
433404 DEFAULT_TRANSFORM_TOPIC, rclcpp::SystemDefaultsQoS ());
@@ -438,8 +409,8 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
438409 // keeping track of odom and base_link transforms only
439410 auto & odometry_transform_message = realtime_odometry_transform_publisher_->msg_ ;
440411 odometry_transform_message.transforms .resize (1 );
441- odometry_transform_message.transforms .front ().header .frame_id = odom_params_ .odom_frame_id ;
442- odometry_transform_message.transforms .front ().child_frame_id = odom_params_ .base_frame_id ;
412+ odometry_transform_message.transforms .front ().header .frame_id = params_ .odom_frame_id ;
413+ odometry_transform_message.transforms .front ().child_frame_id = params_ .base_frame_id ;
443414 }
444415
445416 // Create odom reset service
@@ -456,8 +427,8 @@ CallbackReturn TricycleController::on_activate(const rclcpp_lifecycle::State &)
456427 RCLCPP_INFO (get_node ()->get_logger (), " On activate: Initialize Joints" );
457428
458429 // Initialize the joints
459- const auto wheel_front_result = get_traction (traction_joint_name_ , traction_joint_);
460- const auto steering_result = get_steering (steering_joint_name_ , steering_joint_);
430+ const auto wheel_front_result = get_traction (params_. traction_joint_name , traction_joint_);
431+ const auto steering_result = get_steering (params_. steering_joint_name , steering_joint_);
461432 if (wheel_front_result == CallbackReturn::ERROR || steering_result == CallbackReturn::ERROR)
462433 {
463434 return CallbackReturn::ERROR;
@@ -644,12 +615,12 @@ std::tuple<double, double> TricycleController::twist_to_ackermann(double Vx, dou
644615 if (Vx == 0 && theta_dot != 0 )
645616 { // is spin action
646617 alpha = theta_dot > 0 ? M_PI_2 : -M_PI_2;
647- Ws = abs (theta_dot) * wheel_params_ .wheelbase / wheel_params_. radius ;
618+ Ws = abs (theta_dot) * params_ .wheelbase / params_. wheel_radius ;
648619 return std::make_tuple (alpha, Ws);
649620 }
650621
651- alpha = convert_trans_rot_vel_to_steering_angle (Vx, theta_dot, wheel_params_ .wheelbase );
652- Ws = Vx / (wheel_params_. radius * std::cos (alpha));
622+ alpha = convert_trans_rot_vel_to_steering_angle (Vx, theta_dot, params_ .wheelbase );
623+ Ws = Vx / (params_. wheel_radius * std::cos (alpha));
653624 return std::make_tuple (alpha, Ws);
654625}
655626
0 commit comments