diff --git a/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index fff534012ba..879a83a1699 100644 --- a/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -52,7 +52,7 @@ class EKFLocalizer: public carma_ros2_utils::CarmaLifecycleNode rclcpp::Publisher::SharedPtr pub_yaw_bias_; //!< @brief ekf estimated yaw bias publisher rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief initial pose subscriber - rclcpp::Subscription::SharedPtr sub_pose_with_cov_; //!< @brief measurement pose with covariance subscriber + rclcpp::Subscription::SharedPtr sub_pose_with_cov_; //!< @brief measurement pose with covariance subscriber rclcpp::Subscription::SharedPtr sub_pose_; //!< @brief measurement pose subscriber rclcpp::Subscription::SharedPtr sub_twist_with_cov_; //!< @brief measurement twist with covariance subscriber rclcpp::Subscription::SharedPtr sub_twist_; //!< @brief measurement twist subscriber diff --git a/core_perception/ekf_localizer/src/ekf_localizer.cpp b/core_perception/ekf_localizer/src/ekf_localizer.cpp index 6e665502fad..3d56136c8ca 100644 --- a/core_perception/ekf_localizer/src/ekf_localizer.cpp +++ b/core_perception/ekf_localizer/src/ekf_localizer.cpp @@ -114,8 +114,9 @@ namespace ekf_localizer{ pub_twist_ = create_publisher("ekf_twist", 1); pub_twist_cov_ = create_publisher("ekf_twist_with_covariance", 1); pub_yaw_bias_ = create_publisher("estimated_yaw_bias", 1); - sub_initialpose_ = create_subscription("in_pose_with_covariance", 1, std::bind(&EKFLocalizer::callbackPoseWithCovariance, this, std::placeholders::_1)); - sub_pose_with_cov_ = create_subscription("in_pose", 1, std::bind(&EKFLocalizer::callbackPose, this, std::placeholders::_1)); + sub_initialpose_ = create_subscription("initialpose", 1, std::bind(&EKFLocalizer::callbackInitialPose, this, std::placeholders::_1)); + sub_pose_with_cov_ = create_subscription("in_pose_with_covariance", 1, std::bind(&EKFLocalizer::callbackPoseWithCovariance, this, std::placeholders::_1)); + sub_pose_ = create_subscription("in_pose", 1, std::bind(&EKFLocalizer::callbackPose, this, std::placeholders::_1)); sub_twist_with_cov_ = create_subscription("in_twist_with_covariance", 1, std::bind(&EKFLocalizer::callbackTwistWithCovariance, this, std::placeholders::_1)); sub_twist_ = create_subscription("in_twist", 1, std::bind(&EKFLocalizer::callbackTwist, this, std::placeholders::_1));