siemens / ros-sharp

ROS# is a set of open source software libraries and tools in C# for communicating with ROS from .NET applications, in particular Unity3D
Apache License 2.0
988 stars 373 forks source link

Couldn't send byte array properly, ROS2 #389

Closed jim18324 closed 3 years ago

jim18324 commented 3 years ago

I have a question!

Here is my question:

Hi, I'm very new to ROS and Unity. I'm trying to send the raw image/compressed image data from Unity to ROS2 by ros2-web-bridge.

During my experiments, I found out that the image data length increased before passing to ros2-web-bridge. This increment follow an order of dived by 3 and multiply by 4. So if my image size is 100*100 pixels with RGB24 texture format, in theory i will received a byte array with length 300 in the ROS2 side. But in reality, i received a byte array with length 400. This issue happens in default compressed image publisher and raw image publisher. However, if i change byte array to uint array, it work fine. Can you please help me figure this out? The video is the record of the problem that i encountered. https://youtu.be/SzQc338rtjQ

/*
© CentraleSupelec, 2017
Author: Dr. Jeremy Fix (jeremy.fix@centralesupelec.fr)

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
<http://www.apache.org/licenses/LICENSE-2.0>.
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/

// Adjustments to new Publication Timing and Execution Framework 
// © Siemens AG, 2018, Dr. Martin Bischoff (martin.bischoff@siemens.com)

using UnityEngine;

using System.IO;
using System;

namespace RosSharp.RosBridgeClient
{
    public class RawImagePublisher : UnityPublisher<MessageTypes.Sensor.Image>
    {
        public Camera ImageCamera;
        public string FrameId = "Camera";
        public int resolutionWidth = 640;
        public int resolutionHeight = 480;
        public string Encoding = "rgb8";
        public byte Is_bigendian = 0;
        public uint Step = 3*640;

        private MessageTypes.Sensor.Image message;
        private Texture2D texture2D;
        private Rect rect;

        protected override void Start()
        {
            base.Start();
            InitializeGameObject();
            InitializeMessage();
            Camera.onPostRender += UpdateImage;
        }

        private void UpdateImage(Camera _camera)
        {
            if (texture2D != null && _camera == this.ImageCamera)
                UpdateMessage();
        }

        private void InitializeGameObject()
        {
            texture2D = new Texture2D(resolutionWidth, resolutionHeight, TextureFormat.RGBA32, false);
            rect = new Rect(0, 0, resolutionWidth, resolutionHeight);
            ImageCamera.targetTexture = new RenderTexture(resolutionWidth, resolutionHeight, 24);
        }

        private void InitializeMessage()
        {
            message = new MessageTypes.Sensor.Image();
            message.header.frame_id = FrameId;
            message.height = Convert.ToUInt32(resolutionHeight);
            message.width = Convert.ToUInt32(resolutionWidth);
            message.encoding = Encoding;

            message.is_bigendian = Is_bigendian;
            message.step = Step;
        }

        private void UpdateMessage()
        {
            message.header.Update();
            texture2D.ReadPixels(rect, 0, 0);
            byte [] image =  texture2D.GetRawTextureData();

            // Works with Uint[]
            // message.data = new uint[image.Length];
            // for(int i=0; i < message.data.Length; i+=4){
            //     message.data[message.data.Length-i-4] = Convert.ToUInt32(image[i]);
            //     message.data[message.data.Length-i-3] = Convert.ToUInt32(image[i+1]);
            //     message.data[message.data.Length-i-2] = Convert.ToUInt32(image[i+2]);
            //     message.data[message.data.Length-i-1] = Convert.ToUInt32(image[i+3]);
            // }

            // Doesn't work with byte[]
            message.data = new byte[image.Length];
            for(int i=0; i < message.data.Length; i+=4){
                message.data[message.data.Length-i-4] = image[i];
                message.data[message.data.Length-i-3] = image[i+1];
                message.data[message.data.Length-i-2] = image[i+2];
                message.data[message.data.Length-i-1] = image[i+3];
            }

            Publish(message);
        }

    }
}
MartinBischoff commented 3 years ago

I never experienced this error in any of my projects but I presume the serialization on the Unity side or the deserailization on ros2-web-bridge is the problem. I'd suggest you check the length of the byte[] that leaves Unity (e.g. in RosSocket Line 173 or in the actual protocol or serializer that you are using).

The image data is at no point artificially extendend, see CompressedImage and ImagePublisher.