diff --git a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp index 7bdad81ba..3fd6ca24c 100644 --- a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp +++ b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp @@ -268,7 +268,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr } impl_->last_update_time_ = _model->GetWorld()->SimTime(); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + rmw_qos_profile_t qos_profile = rmw_qos_profile_default; + qos_profile.depth = 1; impl_->cmd_vel_sub_ = impl_->ros_node_->create_subscription( "cmd_vel", std::bind(&GazeboRosDiffDrivePrivate::OnCmdVel, impl_.get(), std::placeholders::_1), diff --git a/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp b/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp index 070026b57..182c04187 100644 --- a/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp @@ -60,12 +60,11 @@ TEST_F(GazeboRosDiffDriveTest, Publishing) // Create subscriber nav_msgs::msg::Odometry::SharedPtr latestMsg; - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto sub = node->create_subscription( "test/odom_test", [&latestMsg](const nav_msgs::msg::Odometry::SharedPtr _msg) { latestMsg = _msg; - }, qos_profile); + }); // Send command auto pub = node->create_publisher("test/cmd_test");