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

Add namespace option to launchfile #7

Open
wants to merge 3 commits into
base: eloquent-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 37 additions & 8 deletions slam_gmapping/launch/slam_gmapping.launch.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,41 @@
from launch import LaunchDescription
from launch.substitutions import EnvironmentVariable
import launch.actions
import launch_ros.actions
from launch.actions import DeclareLaunchArgument, GroupAction
from launch_ros.actions import Node, PushRosNamespace
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration


def generate_launch_description():
use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time', default='true')
return LaunchDescription([
launch_ros.actions.Node(
package='slam_gmapping', node_executable='slam_gmapping', output='screen', parameters=[{'use_sim_time':use_sim_time}]),
])
namespace = LaunchConfiguration("namespace")
use_sim_time = LaunchConfiguration("use_sim_time")
declare_namespace_cmd = DeclareLaunchArgument(
"namespace", default_value="", description="Top-level namespace"
)
declare_use_sim_time_cmd = DeclareLaunchArgument(
"use_sim_time",
default_value="true",
description="Use simulation (Gazebo) clock if true",
)

# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
# https://github.com/ros/geometry2/issues/32
# https://github.com/ros/robot_state_publisher/pull/30
remappings = [("/tf", "tf"), ("/tf_static", "tf_static")]

# Create the launch description and populate
ld = LaunchDescription(
[
declare_namespace_cmd,
declare_use_sim_time_cmd,
Node(
package="slam_gmapping",
namespace=namespace,
executable="slam_gmapping",
output="screen",
parameters=[{"use_sim_time": use_sim_time}],
remappings=remappings,
),
]
)
return ld
4 changes: 2 additions & 2 deletions slam_gmapping/src/slam_gmapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,8 @@ void SlamGmapping::init() {

void SlamGmapping::startLiveSlam() {
entropy_publisher_ = this->create_publisher<std_msgs::msg::Float64>("entropy", rclcpp::SystemDefaultsQoS());
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map", rclcpp::SystemDefaultsQoS());
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>("map_metadata", rclcpp::SystemDefaultsQoS());
sst_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
sstm_ = this->create_publisher<nav_msgs::msg::MapMetaData>("map_metadata", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
scan_filter_sub_ = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>
(node_, "scan", rclcpp::SensorDataQoS().get_rmw_qos_profile());
// sub_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
Expand Down