diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 846dc2aa42..e09e2cc08c 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -61,8 +61,10 @@ DiffDriveController::init(const std::string & controller_name) try { auto node = get_node(); // with the lifecycle node being initialized, we can declare parameters - node->declare_parameter>("left_wheel_names", {}); - node->declare_parameter>("right_wheel_names", {}); + node->declare_parameter>( + "left_wheel_names", std::vector()); + node->declare_parameter>( + "right_wheel_names", std::vector()); node->declare_parameter("wheel_separation", wheel_params_.separation); node->declare_parameter("wheels_per_side", wheel_params_.wheels_per_side); @@ -79,8 +81,9 @@ DiffDriveController::init(const std::string & controller_name) node->declare_parameter("odom_frame_id", odom_params_.odom_frame_id); node->declare_parameter("base_frame_id", odom_params_.base_frame_id); - node->declare_parameter>("pose_covariance_diagonal", {}); - node->declare_parameter>("twist_covariance_diagonal", {}); + node->declare_parameter>("pose_covariance_diagonal", std::vector()); + node->declare_parameter>( + "twist_covariance_diagonal", std::vector()); node->declare_parameter("open_loop", odom_params_.open_loop); node->declare_parameter("enable_odom_tf", odom_params_.enable_odom_tf); diff --git a/forward_command_controller/src/forward_command_controller.cpp b/forward_command_controller/src/forward_command_controller.cpp index 4b1fd57439..2ce5c96d97 100644 --- a/forward_command_controller/src/forward_command_controller.cpp +++ b/forward_command_controller/src/forward_command_controller.cpp @@ -44,7 +44,7 @@ ForwardCommandController::init(const std::string & controller_name) try { auto node = get_node(); - node->declare_parameter>("joints", {}); + node->declare_parameter>("joints", std::vector()); node->declare_parameter("interface_name", ""); } catch (const std::exception & e) { diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 83b5de96ce..855afafdcf 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -589,7 +589,7 @@ JointTrajectoryController::on_activate(const rclcpp_lifecycle::State &) command_interfaces_, joint_names_, interface, joint_command_interface_[index])) { RCLCPP_ERROR( - node_->get_logger(), "Expected %u '%s' command interfaces, got %u.", + node_->get_logger(), "Expected %zu '%s' command interfaces, got %zu.", joint_names_.size(), interface.c_str(), joint_command_interface_[index].size()); return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; } @@ -602,7 +602,7 @@ JointTrajectoryController::on_activate(const rclcpp_lifecycle::State &) state_interfaces_, joint_names_, interface, joint_state_interface_[index])) { RCLCPP_ERROR( - node_->get_logger(), "Expected %u '%s' state interfaces, got %u.", + node_->get_logger(), "Expected %zu '%s' state interfaces, got %zu.", joint_names_.size(), interface.c_str(), joint_state_interface_[index].size()); return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; }