diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index c10dab88e..3e61224eb 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -210,14 +210,25 @@ static void ConvertImage(T &self, EColorConverter cc) { throw std::invalid_argument("invalid color converter!"); } } + +// image object resturned from optical flow to color conversion +class FakeImage : public std::vector { + public: + unsigned int Width = 0; + unsigned int Height = 0; + float FOV = 0; +}; // method to convert optical flow images to rgb -static std::vector ColorCodedFlow ( +static FakeImage ColorCodedFlow ( carla::sensor::data::OpticalFlowImage& image) { namespace bp = boost::python; namespace csd = carla::sensor::data; constexpr float pi = 3.1415f; constexpr float rad2ang = 360.f/(2.f*pi); - std::vector result; + FakeImage result; + result.Width = image.GetWidth(); + result.Height = image.GetHeight(); + result.FOV = image.GetFOVAngle(); result.resize(image.GetHeight()*image.GetWidth()* 4); // lambda for computing batches of pixels @@ -353,10 +364,14 @@ void export_sensor_data() { namespace csd = carla::sensor::data; namespace css = carla::sensor::s11n; - // wrapper for std::vector - class_ >("VecUint8") - .def(vector_indexing_suite >()) - .add_property("raw_data", &GetRawDataAsBuffer >); + // Fake image returned from optical flow to color conversion + // fakes the regular image object + class_("FakeImage", no_init) + .def(vector_indexing_suite>()) + .add_property("width", &FakeImage::Width) + .add_property("height", &FakeImage::Height) + .add_property("fov", &FakeImage::FOV) + .add_property("raw_data", &GetRawDataAsBuffer); class_>("SensorData", no_init) .add_property("frame", &cs::SensorData::GetFrame) diff --git a/PythonAPI/examples/manual_control.py b/PythonAPI/examples/manual_control.py index 2ac233493..a14f072cd 100755 --- a/PythonAPI/examples/manual_control.py +++ b/PythonAPI/examples/manual_control.py @@ -1084,8 +1084,8 @@ class CameraManager(object): dvs_img[dvs_events[:]['y'], dvs_events[:]['x'], dvs_events[:]['pol'] * 2] = 255 self.surface = pygame.surfarray.make_surface(dvs_img.swapaxes(0, 1)) elif self.sensors[self.index][0].startswith('sensor.camera.optical_flow'): - array = image.get_color_coded_flow() - array = np.frombuffer(array, dtype=np.dtype("uint8")) + image = image.get_color_coded_flow() + array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) array = np.reshape(array, (image.height, image.width, 4)) array = array[:, :, :3] array = array[:, :, ::-1]