@@ -54,13 +54,13 @@ AssistedTeleopBehaviorTester::AssistedTeleopBehaviorTester()
5454 node_->create_publisher <std_msgs::msg::Empty>(" preempt_teleop" , 10 );
5555
5656 cmd_vel_pub_ =
57- node_->create_publisher <geometry_msgs::msg::Twist >(" cmd_vel_teleop" , 10 );
57+ node_->create_publisher <geometry_msgs::msg::TwistStamped >(" cmd_vel_teleop" , 10 );
5858
5959 subscription_ = node_->create_subscription <geometry_msgs::msg::PoseWithCovarianceStamped>(
6060 " amcl_pose" , rclcpp::QoS (rclcpp::KeepLast (1 )).transient_local ().reliable (),
6161 std::bind (&AssistedTeleopBehaviorTester::amclPoseCallback, this , std::placeholders::_1));
6262
63- filtered_vel_sub_ = node_->create_subscription <geometry_msgs::msg::Twist >(
63+ filtered_vel_sub_ = node_->create_subscription <geometry_msgs::msg::TwistStamped >(
6464 " cmd_vel" ,
6565 rclcpp::SystemDefaultsQoS (),
6666 std::bind (&AssistedTeleopBehaviorTester::filteredVelCallback, this , std::placeholders::_1));
@@ -167,9 +167,9 @@ bool AssistedTeleopBehaviorTester::defaultAssistedTeleopTest(
167167 counter_ = 0 ;
168168 auto start_time = std::chrono::system_clock::now ();
169169 while (rclcpp::ok ()) {
170- geometry_msgs::msg::Twist cmd_vel = geometry_msgs::msg::Twist ();
171- cmd_vel.linear .x = lin_vel;
172- cmd_vel.angular .z = ang_vel;
170+ geometry_msgs::msg::TwistStamped cmd_vel = geometry_msgs::msg::TwistStamped ();
171+ cmd_vel.twist . linear .x = lin_vel;
172+ cmd_vel.twist . angular .z = ang_vel;
173173 cmd_vel_pub_->publish (cmd_vel);
174174
175175 if (counter_ > 1 ) {
@@ -265,9 +265,9 @@ void AssistedTeleopBehaviorTester::amclPoseCallback(
265265}
266266
267267void AssistedTeleopBehaviorTester::filteredVelCallback (
268- geometry_msgs::msg::Twist ::SharedPtr msg)
268+ geometry_msgs::msg::TwistStamped ::SharedPtr msg)
269269{
270- if (msg->linear .x == 0 .0f ) {
270+ if (msg->twist . linear .x == 0 .0f ) {
271271 counter_++;
272272 } else {
273273 counter_ = 0 ;
0 commit comments