@@ -185,11 +185,16 @@ private Task OnPublishLeftRGBImageDelegate(ZORGBCamera rgbCamera, string cameraI
185185 _leftImageMessage . header . Update ( ) ;
186186 _leftImageMessage . height = ( uint ) height ;
187187 _leftImageMessage . width = ( uint ) width ;
188- _leftImageMessage . encoding = "rgb8" ;
189188 _leftImageMessage . is_bigendian = 0 ;
190- _leftImageMessage . step = 1 * 3 * ( uint ) width ;
191189 _leftImageMessage . data = rgbData ;
192- // ROSBridgeConnection.Publish<ImageMessage>(_rosImageMessage, _imageROSTopic, Name);
190+
191+ if ( LeftCameraSensor . IsMonochrome == true ) {
192+ _leftImageMessage . step = ( uint ) width ;
193+ _leftImageMessage . encoding = "mono8" ;
194+ } else { // RGB
195+ _leftImageMessage . step = 1 * 3 * ( uint ) width ;
196+ _leftImageMessage . encoding = "rgb8" ;
197+ }
193198
194199 // setup and send CameraInfo message
195200 _leftCameraInfoMessage . Update ( ) ;
@@ -203,7 +208,6 @@ private Task OnPublishLeftRGBImageDelegate(ZORGBCamera rgbCamera, string cameraI
203208 _leftCameraInfoMessage . BuildCameraInfo ( ( uint ) LeftCameraSensor . Width , ( uint ) LeftCameraSensor . Height , ( double ) LeftCameraSensor . FieldOfViewDegrees ) ;
204209 }
205210
206- // ROSBridgeConnection.Publish<CameraInfoMessage>(_rosCameraInfoMessage, _cameraInfoROSTopic, cameraId);
207211 UpdateCameraSynchronization ( ) ;
208212
209213 return Task . CompletedTask ;
@@ -235,11 +239,16 @@ private Task OnPublishRightRGBImageDelegate(ZORGBCamera rgbCamera, string camera
235239 _rightImageMessage . header . Update ( ) ;
236240 _rightImageMessage . height = ( uint ) height ;
237241 _rightImageMessage . width = ( uint ) width ;
238- _rightImageMessage . encoding = "rgb8" ;
239242 _rightImageMessage . is_bigendian = 0 ;
240- _rightImageMessage . step = 1 * 3 * ( uint ) width ;
241243 _rightImageMessage . data = rgbData ;
242- // ROSBridgeConnection.Publish<ImageMessage>(_rosImageMessage, _imageROSTopic, Name);
244+
245+ if ( RightCameraSensor . IsMonochrome == true ) {
246+ _rightImageMessage . step = ( uint ) width ;
247+ _rightImageMessage . encoding = "mono8" ;
248+ } else { // RGB
249+ _rightImageMessage . step = 1 * 3 * ( uint ) width ;
250+ _rightImageMessage . encoding = "rgb8" ;
251+ }
243252
244253 // setup and send CameraInfo message
245254 _rightCameraInfoMessage . Update ( ) ;
@@ -253,7 +262,6 @@ private Task OnPublishRightRGBImageDelegate(ZORGBCamera rgbCamera, string camera
253262 _rightCameraInfoMessage . BuildCameraInfo ( ( uint ) RightCameraSensor . Width , ( uint ) RightCameraSensor . Height , ( double ) RightCameraSensor . FieldOfViewDegrees ) ;
254263 }
255264
256- // ROSBridgeConnection.Publish<CameraInfoMessage>(_rightCameraInfoMessage, _cameraInfoROSTopic, cameraId);
257265 UpdateCameraSynchronization ( ) ;
258266
259267 return Task . CompletedTask ;
0 commit comments