diff --git a/src/pointcloud_to_laserscan/src/pointcloud_to_laserscan_node.cpp b/src/pointcloud_to_laserscan/src/pointcloud_to_laserscan_node.cpp index 5ade22eb..7a620eac 100755 --- a/src/pointcloud_to_laserscan/src/pointcloud_to_laserscan_node.cpp +++ b/src/pointcloud_to_laserscan/src/pointcloud_to_laserscan_node.cpp @@ -68,9 +68,7 @@ PointCloudToLaserScanNode::PointCloudToLaserScanNode(const rclcpp::NodeOptions & rclcpp::PublisherOptions optionsqos; rclcpp::QoS qos(0); - //set the reliable settings to reliable qos.reliable(); - //qos.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE); optionsqos.use_default_callbacks = true; diff --git a/src/rm_urdf_ff/launch/display_launch.py b/src/rm_urdf_ff/launch/display_launch.py index b714838e..40c862bc 100644 --- a/src/rm_urdf_ff/launch/display_launch.py +++ b/src/rm_urdf_ff/launch/display_launch.py @@ -37,7 +37,7 @@ def generate_launch_description(): # Declare the launch options ld.add_action(start_robot_state_publisher_cmd) ld.add_action(joint_state_publisher_gui_cmd) - ld.add_action(start_rviz_cmd) + # ld.add_action(start_rviz_cmd)