Skip to content

Commit

Permalink
Change QoS profile using rclcpp::QoS due to deprecated function
Browse files Browse the repository at this point in the history
  • Loading branch information
hyunseok-yang committed Oct 7, 2020
1 parent 9d14ed0 commit d8bdfc8
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 8 deletions.
2 changes: 1 addition & 1 deletion lidar_driver_sim/src/LidarDriverSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void LidarDriverSim::Initialize()
}

// ROS2 Publisher
pubLaser = this->create_publisher<sensor_msgs::msg::LaserScan>(topic_name_, rcl_publisher_get_default_options().qos);
pubLaser = this->create_publisher<sensor_msgs::msg::LaserScan>(topic_name_, rclcpp::QoS(10));
}

void LidarDriverSim::Deinitialize()
Expand Down
8 changes: 4 additions & 4 deletions micom_driver_sim/src/MicomDriverSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,17 +109,17 @@ void MicomDriverSim::Initialize()
}

// ROS2 Publisher
pubBatteryState_ = create_publisher<sensor_msgs::msg::BatteryState>("battery_state", rcl_publisher_get_default_options().qos);
pubOdometry_ = create_publisher<nav_msgs::msg::Odometry>("odom", rcl_publisher_get_default_options().qos);
pubImu_ = create_publisher<sensor_msgs::msg::Imu>("imu", rcl_publisher_get_default_options().qos);
pubBatteryState_ = create_publisher<sensor_msgs::msg::BatteryState>("battery_state", rclcpp::QoS(10));
pubOdometry_ = create_publisher<nav_msgs::msg::Odometry>("odom", rclcpp::QoS(10));
pubImu_ = create_publisher<sensor_msgs::msg::Imu>("imu", rclcpp::QoS(10));

auto callback_sub = [this](const geometry_msgs::msg::Twist::SharedPtr msg) -> void {
const auto msgBuf = MakeControlMessage(msg);
MicomWrite(msgBuf.data(), msgBuf.size());
};

// ROS2 Subscriber
subMicom_ = create_subscription<geometry_msgs::msg::Twist>("cmd_vel", callback_sub, rcl_publisher_get_default_options().qos);
subMicom_ = create_subscription<geometry_msgs::msg::Twist>("cmd_vel", rclcpp::QoS(10), callback_sub);
}


Expand Down
1 change: 0 additions & 1 deletion realsense_driver_sim/src/RealSenseDriverSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ void RealSenseDriverSim::Initialize()
pSimBridgeInfo->Connect(SimBridge::Mode::CLIENT, portInfo, GetMainHashKey() + "Info");
GetActivatedModules(pSimBridgeInfo);

// GetActivatedModules(pSimBridgeInfo);
const auto transform = GetObjectTransform(pSimBridgeInfo);
SetupStaticTf2(transform, GetPartsName() + "_link");
}
Expand Down
3 changes: 1 addition & 2 deletions unity_ros/src/unity_ros_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ UnityRosInit::UnityRosInit()

// Offer transient local durability on the clock topic so that if publishing is infrequent,
// late subscribers can receive the previously published message(s).
clock_pub_ = create_publisher<rosgraph_msgs::msg::Clock>("/clock",
rclcpp::QoS(rclcpp::KeepLast(10)).transient_local());
clock_pub_ = create_publisher<rosgraph_msgs::msg::Clock>("/clock", rclcpp::QoS(10));

Start();
}
Expand Down

0 comments on commit d8bdfc8

Please sign in to comment.