Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 7 additions & 4 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::vector<std::string>>("left_wheel_names", {});
node->declare_parameter<std::vector<std::string>>("right_wheel_names", {});
node->declare_parameter<std::vector<std::string>>(
"left_wheel_names", std::vector<std::string>());
node->declare_parameter<std::vector<std::string>>(
"right_wheel_names", std::vector<std::string>());

node->declare_parameter<double>("wheel_separation", wheel_params_.separation);
node->declare_parameter<int>("wheels_per_side", wheel_params_.wheels_per_side);
Expand All @@ -79,8 +81,9 @@ DiffDriveController::init(const std::string & controller_name)

node->declare_parameter<std::string>("odom_frame_id", odom_params_.odom_frame_id);
node->declare_parameter<std::string>("base_frame_id", odom_params_.base_frame_id);
node->declare_parameter<std::vector<double>>("pose_covariance_diagonal", {});
node->declare_parameter<std::vector<double>>("twist_covariance_diagonal", {});
node->declare_parameter<std::vector<double>>("pose_covariance_diagonal", std::vector<double>());
node->declare_parameter<std::vector<double>>(
"twist_covariance_diagonal", std::vector<double>());
node->declare_parameter<bool>("open_loop", odom_params_.open_loop);
node->declare_parameter<bool>("enable_odom_tf", odom_params_.enable_odom_tf);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ ForwardCommandController::init(const std::string & controller_name)

try {
auto node = get_node();
node->declare_parameter<std::vector<std::string>>("joints", {});
node->declare_parameter<std::vector<std::string>>("joints", std::vector<std::string>());

node->declare_parameter<std::string>("interface_name", "");
} catch (const std::exception & e) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand Down