Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Diff drive: Reliable QoS with depth of 1 #819

Merged
merged 1 commit into from Sep 11, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 2 additions & 1 deletion gazebo_plugins/src/gazebo_ros_diff_drive.cpp
Expand Up @@ -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<geometry_msgs::msg::Twist>(
"cmd_vel", std::bind(&GazeboRosDiffDrivePrivate::OnCmdVel, impl_.get(),
std::placeholders::_1),
Expand Down
3 changes: 1 addition & 2 deletions gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp
Expand Up @@ -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<nav_msgs::msg::Odometry>(
"test/odom_test",
[&latestMsg](const nav_msgs::msg::Odometry::SharedPtr _msg) {
latestMsg = _msg;
}, qos_profile);
});

// Send command
auto pub = node->create_publisher<geometry_msgs::msg::Twist>("test/cmd_test");
Expand Down