Skip to content

Commit

Permalink
Added namespace to mappings
Browse files Browse the repository at this point in the history
Signed-off-by: Jakub Delicat <[email protected]>
  • Loading branch information
delihus committed Dec 5, 2023
1 parent 7eab9e8 commit 967df74
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 15 deletions.
2 changes: 1 addition & 1 deletion rosbot_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,9 @@ def generate_launch_description():
robot_localization_node = Node(
package="robot_localization",
executable="ekf_node",
name="ekf_filter_node",
output="screen",
parameters=[ekf_config],
arguments=["--ros-args --log-level debug"],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
Expand Down
20 changes: 10 additions & 10 deletions rosbot_gazebo/config/gz_remappings.yaml
Original file line number Diff line number Diff line change
@@ -1,39 +1,39 @@
- topic_name: "/scan"
- topic_name: "<robot_namespace>/scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"

- topic_name: "/camera/camera_info"
- topic_name: "<robot_namespace>/camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "ignition.msgs.CameraInfo"

- topic_name: "/camera/depth_image"
- topic_name: "<robot_namespace>/camera/depth_image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"

- topic_name: "/camera/image"
- topic_name: "<robot_namespace>/camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"

- topic_name: "/camera/points"
- topic_name: "<robot_namespace>/camera/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "ignition.msgs.PointCloudPacked"

- topic_name: "/clock"
- topic_name: "<robot_namespace>/clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "ignition.msgs.Clock"

- topic_name: "/range/fl"
- topic_name: "<robot_namespace>/range/fl"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"

- topic_name: "/range/fr"
- topic_name: "<robot_namespace>/range/fr"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"

- topic_name: "/range/rl"
- topic_name: "<robot_namespace>/range/rl"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"

- topic_name: "/range/rr"
- topic_name: "<robot_namespace>/range/rr"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"
18 changes: 14 additions & 4 deletions rosbot_gazebo/launch/spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
)
from launch.substitutions import PathJoinSubstitution, LaunchConfiguration, PythonExpression
from launch.launch_description_sources import PythonLaunchDescriptionSource

from nav2_common.launch import ReplaceString
from launch_ros.actions import Node, SetParameter

from ament_index_python.packages import get_package_share_directory
Expand All @@ -33,6 +33,10 @@ def generate_launch_description():
description="Namespace for all topics and tfs",
)

namespace_ext = PythonExpression(
["''", " if '", namespace, "' == '' ", "else ", "'/", namespace, "'"]
)

mecanum = LaunchConfiguration("mecanum")
declare_mecanum_arg = DeclareLaunchArgument(
"mecanum",
Expand Down Expand Up @@ -64,6 +68,11 @@ def generate_launch_description():
[get_package_share_directory("rosbot_gazebo"), "config", "gz_remappings.yaml"]
)

namespaced_gz_remappings_file = ReplaceString(
source_file=gz_remappings_file,
replacements={"<robot_namespace>": (namespace_ext)},
)

gz_spawn_entity = Node(
package="ros_gz_sim",
executable="create",
Expand Down Expand Up @@ -95,7 +104,7 @@ def generate_launch_description():
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_bridge",
parameters=[{"config_file": gz_remappings_file}],
parameters=[{"config_file": namespaced_gz_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
Expand Down Expand Up @@ -138,9 +147,10 @@ def generate_launch_description():
"1.57",
"-1.57",
"0.0",
# Here should be namespace
"camera_depth_optical_frame",
"rosbot/base_link/camera_orbbec_astra_camera",
LaunchConfiguration(
"gazebo_frame", default=[robot_name, "/base_link/camera_orbbec_astra_camera"]
),
],
remappings=[
("/tf", "tf"),
Expand Down
1 change: 1 addition & 0 deletions rosbot_gazebo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
for details refer to the ros_gz_sim package -->
<exec_depend>ros_gz_bridge</exec_depend>
<exec_depend>ign_ros2_control</exec_depend>
<exec_depend>nav2_common</exec_depend>

<test_depend>python3-pytest</test_depend>
<test_depend>launch</test_depend>
Expand Down

0 comments on commit 967df74

Please sign in to comment.