diff --git a/ros/ros2/OdometryServer.cpp b/ros/ros2/OdometryServer.cpp index ae54ab61..4907d948 100644 --- a/ros/ros2/OdometryServer.cpp +++ b/ros/ros2/OdometryServer.cpp @@ -56,7 +56,7 @@ OdometryServer::OdometryServer(const rclcpp::NodeOptions &options) child_frame_ = declare_parameter("child_frame", child_frame_); odom_frame_ = declare_parameter("odom_frame", odom_frame_); publish_alias_tf_ = declare_parameter("publish_alias_tf", publish_alias_tf_); - publish_odom_tf_ = declare_parameter("publish_odom_tf", publish_alias_tf_); + publish_odom_tf_ = declare_parameter("publish_odom_tf", publish_odom_tf_); config_.max_range = declare_parameter("max_range", config_.max_range); config_.min_range = declare_parameter("min_range", config_.min_range); config_.deskew = declare_parameter("deskew", config_.deskew);