Skip to content

Commit

Permalink
[ekf_localizer] [pose_initializer] fix topic message type (autowarefo…
Browse files Browse the repository at this point in the history
…undation#176)

Co-authored-by: Autoware <[email protected]>
Co-authored-by: Takamasa Horibe <[email protected]>
  • Loading branch information
3 people authored Dec 15, 2020
1 parent 60f1486 commit 08f97ff
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,24 +102,24 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti
"ekf_pose_without_yawbias", 1);
pub_pose_cov_no_yawbias_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"ekf_pose_with_covariance_without_yawbias", 1);
sub_initialpose_ = create_subscription<geometry_msgs::msg::PoseStamped>(
sub_initialpose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"initialpose", 1, std::bind(
&EKFLocalizer::callbackInitialPose, this,
_1));
sub_pose_with_cov_ =
create_subscription<geometry_msgs::msg::PoseStamped>(
create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"in_pose_with_covariance", 1,
std::bind(&EKFLocalizer::callbackPoseWithCovariance, this, _1));
sub_pose_ =
create_subscription<geometry_msgs::msg::TwistStamped>(
create_subscription<geometry_msgs::msg::PoseStamped>(
"in_pose", 1,
std::bind(&EKFLocalizer::callbackPose, this, _1));
sub_twist_with_cov_ =
create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"in_twist_with_covariance",
1,
std::bind(&EKFLocalizer::callbackTwistWithCovariance, this, _1));
sub_twist_ = create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
sub_twist_ = create_subscription<geometry_msgs::msg::TwistStamped>(
"in_twist", 1, std::bind(
&EKFLocalizer::callbackTwist, this,
_1));
Expand Down

0 comments on commit 08f97ff

Please sign in to comment.