Skip to content

None sensor patch #63

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

Merged
merged 2 commits into from
Mar 20, 2024
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions .github/workflows/industrial_ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,13 @@ jobs:
# For more information see https://github.com/micro-ROS/micro_ros_msgs/issues/7
sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i

- name: Leave only ROSbot tests
shell: bash
run: |
sed '/if(BUILD_TESTING)/,/endif()/d' src/diff_drive_controller/CMakeLists.txt -i
sed '/if(BUILD_TESTING)/,/endif()/d' src/imu_sensor_broadcaster/CMakeLists.txt -i
sed '/if(BUILD_TESTING)/,/endif()/d' src/micro_ros_msgs/CMakeLists.txt -i

- uses: ros-industrial/industrial_ci@master
env:
ROS_DISTRO: ${{matrix.ROS_DISTRO}}
Expand Down
187 changes: 98 additions & 89 deletions rosbot_xl_gazebo/launch/spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ def launch_gz_bridge(context: LaunchContext, *args, **kwargs):
lidar_model = context.perform_substitution(LaunchConfiguration("lidar_model"))
camera_model = context.perform_substitution(LaunchConfiguration("camera_model"))
namespace = context.perform_substitution(LaunchConfiguration("namespace"))
actions = []

pointcloud_rpy = [
"1.57",
Expand All @@ -55,105 +56,113 @@ def launch_gz_bridge(context: LaunchContext, *args, **kwargs):
if lidar_model.startswith("slamtec_rplidar"):
lidar_model = "slamtec_rplidar"

gz_lidar_remappings_file = PathJoinSubstitution(
[
get_package_share_directory("rosbot_xl_gazebo"),
"config",
LaunchConfiguration(
"gz_lidar_remappings_file",
default=["gz_", lidar_model, "_remappings.yaml"],
),
]
)

namespaced_gz_lidar_remappings_file = ReplaceString(
source_file=gz_lidar_remappings_file,
replacements={"<robot_namespace>": namespace_ext},
)
if lidar_model != "None":
gz_lidar_remappings_file = PathJoinSubstitution(
[
get_package_share_directory("rosbot_xl_gazebo"),
"config",
LaunchConfiguration(
"gz_lidar_remappings_file",
default=["gz_", lidar_model, "_remappings.yaml"],
),
]
)

ign_lidar_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_lidar_bridge",
parameters=[{"config_file": namespaced_gz_lidar_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
output="screen",
namespace=namespace,
condition=LaunchConfigurationNotEquals(lidar_model, "None"),
)
namespaced_gz_lidar_remappings_file = ReplaceString(
source_file=gz_lidar_remappings_file,
replacements={"<robot_namespace>": namespace_ext},
)

zed_model = None
if camera_model.startswith("stereolabs_zed"):
zed_model = camera_model.replace("stereolabs_", "")
camera_model = "stereolabs_zed"
depth_camera_child_tf = "rosbot_xl/base_link/camera_" + camera_model + "_depth"
depth_camera_parent_tf = "camera_center_optical_frame"
pointcloud_rpy = ["0", "0", "0"]
actions.append(
Node(
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_lidar_bridge",
parameters=[{"config_file": namespaced_gz_lidar_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
output="screen",
namespace=namespace,
condition=LaunchConfigurationNotEquals(lidar_model, "None"),
)
)

gz_camera_remappings_file = PathJoinSubstitution(
[
get_package_share_directory("rosbot_xl_gazebo"),
"config",
LaunchConfiguration(
"gz_camera_remappings_file",
default=["gz_", camera_model, "_remappings.yaml"],
),
]
)
if camera_model != "None":
zed_model = None
if camera_model.startswith("stereolabs_zed"):
zed_model = camera_model.replace("stereolabs_", "")
camera_model = "stereolabs_zed"
depth_camera_child_tf = "rosbot_xl/base_link/camera_" + camera_model + "_depth"
depth_camera_parent_tf = "camera_center_optical_frame"
pointcloud_rpy = ["0", "0", "0"]

namespaced_gz_camera_remappings_file = ReplaceString(
source_file=gz_camera_remappings_file,
replacements={"<robot_namespace>": namespace_ext},
)
gz_camera_remappings_file = PathJoinSubstitution(
[
get_package_share_directory("rosbot_xl_gazebo"),
"config",
LaunchConfiguration(
"gz_camera_remappings_file",
default=["gz_", camera_model, "_remappings.yaml"],
),
]
)

if zed_model is not None:
namespaced_gz_camera_remappings_file = ReplaceString(
source_file=namespaced_gz_camera_remappings_file,
replacements={"<zed>": zed_model},
source_file=gz_camera_remappings_file,
replacements={"<robot_namespace>": namespace_ext},
)

ign_camera_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_camera_bridge",
parameters=[{"config_file": namespaced_gz_camera_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
output="screen",
namespace=namespace,
condition=LaunchConfigurationNotEquals(camera_model, "None"),
)
if zed_model is not None:
namespaced_gz_camera_remappings_file = ReplaceString(
source_file=namespaced_gz_camera_remappings_file,
replacements={"<zed>": zed_model},
)

# The frame of the point cloud from ignition gazebo 6 isn't provided by <frame_id>.
# See https://github.com/gazebosim/gz-sensors/issues/239
point_cloud_tf = Node(
package="tf2_ros",
executable="static_transform_publisher",
name="point_cloud_tf",
output="log",
arguments=[
"0",
"0",
"0",
]
+ pointcloud_rpy
+ [
depth_camera_parent_tf,
depth_camera_child_tf,
],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
namespace=namespace,
)
actions.append(
Node(
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_camera_bridge",
parameters=[{"config_file": namespaced_gz_camera_remappings_file}],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
output="screen",
namespace=namespace,
condition=LaunchConfigurationNotEquals(camera_model, "None"),
)
)

# The frame of the point cloud from ignition gazebo 6 isn't provided by <frame_id>.
# See https://github.com/gazebosim/gz-sensors/issues/239
actions.append(
Node(
package="tf2_ros",
executable="static_transform_publisher",
name="point_cloud_tf",
output="log",
arguments=[
"0",
"0",
"0",
]
+ pointcloud_rpy
+ [
depth_camera_parent_tf,
depth_camera_child_tf,
],
remappings=[
("/tf", "tf"),
("/tf_static", "tf_static"),
],
namespace=namespace,
)
)

return [ign_lidar_bridge, ign_camera_bridge, point_cloud_tf]
return actions


def generate_launch_description():
Expand Down