diff --git a/localization/yabloc/twist/twist_converter/src/velocity_report_node.cpp b/localization/yabloc/twist/twist_converter/src/velocity_report_node.cpp index 65d81686b557b..65e7ecf803b51 100644 --- a/localization/yabloc/twist/twist_converter/src/velocity_report_node.cpp +++ b/localization/yabloc/twist/twist_converter/src/velocity_report_node.cpp @@ -45,12 +45,12 @@ class VelocityReportEncoder : public rclcpp::Node void on_twist(const TwistStamped & msg) { - VelocityReport velocity_report; + Velocity velocity_report; velocity_report.header = msg.header; velocity_report.longitudinal_velocity = msg.twist.linear.x; velocity_report.lateral_velocity = msg.twist.linear.y; - velocity_report.heading_rate = msg.heading_rate; - pub_twist_stamped_->publish(velocity_report); + velocity_report.heading_rate = msg.twist.angular.z; + pub_velocity_report_->publish(velocity_report); } }; diff --git a/localization/yabloc/twist/twist_estimator/src/twist_estimator_core.cpp b/localization/yabloc/twist/twist_estimator/src/twist_estimator_core.cpp index ce6d37108dff5..40ae80a980ebe 100644 --- a/localization/yabloc/twist/twist_estimator/src/twist_estimator_core.cpp +++ b/localization/yabloc/twist/twist_estimator/src/twist_estimator_core.cpp @@ -37,7 +37,7 @@ TwistEstimator::TwistEstimator() auto cb_velocity = std::bind(&TwistEstimator::on_velocity_report, this, _1); sub_imu_ = create_subscription("/sensing/imu/tamagawa/imu_raw", 10, cb_imu); - sub_velocity_report_ = create_subscription("/vehicle/status/velocity_report", 10, cb_velocity); + sub_velocity_report_ = create_subscription("/vehicle/status/velocity_status", 10, cb_velocity); sub_navpvt_ = create_subscription("/sensing/gnss/ublox/navpvt", 10, cb_pvt); pub_twist_ = create_publisher("twist", 10);