use cyclone_dds for image bridge and use image_bridge command
Build Docs / build (push) Failing after 52s Details

This commit is contained in:
Burak Ozter 2024-11-14 19:15:12 -04:00
parent d5c0b68ceb
commit 308c7087a2
2 changed files with 4 additions and 2 deletions

View File

@ -1,5 +1,5 @@
FROM git.spirirobotics.com/spiri/services-ros2-mavros:main
RUN apt-get update
RUN apt-get --yes install ros-${ROS_DISTRO}-ros-gz-bridge
RUN apt-get --yes install ros-${ROS_DISTRO}-ros-gz-bridge ros-${ROS_DISTRO}-compressed-image-transport ros-${ROS_DISTRO}-rmw-cyclonedds-cpp

View File

@ -5,4 +5,6 @@ services:
network_mode: host
# image: git.spirirobotics.com/spiri/services-ros2-mavros:main
build: ./
command: ros2 run ros_gz_bridge parameter_bridge /world/${WORLD_NAME}/model/${ROBOT_NAME}/link/pitch_link/sensor/camera/image@sensor_msgs/msg/Image@gz.msgs.Image
environment:
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
command: ros2 run ros_gz_image image_bridge /world/${WORLD_NAME}/model/${ROBOT_NAME}/link/pitch_link/sensor/camera/image