diff --git a/libraries/Camera/README.md b/libraries/Camera/README.md
new file mode 100644
index 00000000..8316af35
--- /dev/null
+++ b/libraries/Camera/README.md
@@ -0,0 +1,5 @@
+# 📹 Library for Arduino Supported Cameras
+
+The Arduino camera library captures pixels from supported cameras on Arduino boards and stores them in a buffer for continuous retrieval and processing.
+
+📖 For more information about this library please read the documentation [here](./docs/).
diff --git a/libraries/Camera/examples/CameraCaptureRawBytes/CameraCaptureRawBytes.ino b/libraries/Camera/examples/CameraCaptureRawBytes/CameraCaptureRawBytes.ino
new file mode 100644
index 00000000..fca2252a
--- /dev/null
+++ b/libraries/Camera/examples/CameraCaptureRawBytes/CameraCaptureRawBytes.ino
@@ -0,0 +1,33 @@
+#include "camera.h"
+
+Camera cam;
+
+void fatal_error(const char *msg) {
+  Serial.println(msg);
+  pinMode(LED_BUILTIN, OUTPUT);
+  while (1) {
+      digitalWrite(LED_BUILTIN, HIGH);
+      delay(100);
+      digitalWrite(LED_BUILTIN, LOW);
+      delay(100);
+  }
+}
+
+void setup(void) {
+  Serial.begin(115200);    
+  if (!cam.begin(320, 240, CAMERA_RGB565)) {
+    fatal_error("Camera begin failed");
+  }
+  cam.setVerticalFlip(false);
+  cam.setHorizontalMirror(false);
+}
+
+void loop() {
+  FrameBuffer fb;
+  if (cam.grabFrame(fb)) {
+    if (Serial.read() == 1) {
+      Serial.write(fb.getBuffer(), fb.getBufferSize());
+    }
+    cam.releaseFrame(fb);
+  }
+}
diff --git a/libraries/Camera/extras/CameraRawBytesVisualizer/CameraRawBytesVisualizer.pde b/libraries/Camera/extras/CameraRawBytesVisualizer/CameraRawBytesVisualizer.pde
new file mode 100644
index 00000000..dcb2570b
--- /dev/null
+++ b/libraries/Camera/extras/CameraRawBytesVisualizer/CameraRawBytesVisualizer.pde
@@ -0,0 +1,128 @@
+/*
+  This sketch reads a raw Stream of RGB565 pixels
+  from the Serial port and displays the frame on
+  the window.
+  Use with the Examples -> CameraCaptureRawBytes Arduino sketch.
+  This example code is in the public domain.
+*/
+
+import processing.serial.*;
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+Serial myPort;
+
+// must match resolution used in the Arduino sketch
+final int cameraWidth = 320;
+final int cameraHeight = 240;
+
+// Must match the image mode in the Arduino sketch
+boolean useGrayScale = false;
+
+// Must match the baud rate in the Arduino sketch
+final int baudRate = 115200;
+
+final int cameraBytesPerPixel = useGrayScale ? 1 : 2;
+final int cameraPixelCount = cameraWidth * cameraHeight;
+final int bytesPerFrame = cameraPixelCount * cameraBytesPerPixel;
+final int timeout =  int((bytesPerFrame / float(baudRate / 10)) * 1000 * 2); // Twice the transfer rate
+
+PImage myImage;
+byte[] frameBuffer = new byte[bytesPerFrame];
+int lastUpdate = 0;
+boolean shouldRedraw = false;
+
+void setup() {
+  size(640, 480);  
+
+  // If you have only ONE serial port active you may use this:
+  //myPort = new Serial(this, Serial.list()[0], baudRate);          // if you have only ONE serial port active
+
+  // If you know the serial port name
+  //myPort = new Serial(this, "COM5", baudRate);                    // Windows
+  myPort = new Serial(this, "/dev/ttyACM0", baudRate);            // Linux
+  //myPort = new Serial(this, "/dev/cu.usbmodem14301", baudRate);     // Mac
+
+  // wait for a full frame of bytes
+  myPort.buffer(bytesPerFrame);  
+
+  myImage = createImage(cameraWidth, cameraHeight, ALPHA);
+  
+  // Let the Arduino sketch know we're ready to receive data
+  myPort.write(1);
+}
+
+void draw() {
+  // Time out after a few seconds and ask for new data
+  if(millis() - lastUpdate > timeout) {
+    println("Connection timed out.");    
+    myPort.clear();
+    myPort.write(1);
+  }
+  
+  if(shouldRedraw){    
+    PImage img = myImage.copy();
+    img.resize(640, 480);
+    image(img, 0, 0);
+    shouldRedraw = false;
+  }
+}
+
+int[] convertRGB565ToRGB888(short pixelValue){  
+  //RGB565
+  int r = (pixelValue >> (6+5)) & 0x01F;
+  int g = (pixelValue >> 5) & 0x03F;
+  int b = (pixelValue) & 0x01F;
+  //RGB888 - amplify
+  r <<= 3;
+  g <<= 2;
+  b <<= 3; 
+  return new int[]{r,g,b};
+}
+
+void serialEvent(Serial myPort) {  
+  lastUpdate = millis();
+  
+  // read the received bytes
+  myPort.readBytes(frameBuffer);
+
+  // Access raw bytes via byte buffer  
+  ByteBuffer bb = ByteBuffer.wrap(frameBuffer);
+  
+  // Ensure proper endianness of the data for > 8 bit values.
+  // The 1 byte bb.get() function will always return the bytes in the correct order.
+  bb.order(ByteOrder.BIG_ENDIAN);
+
+  int i = 0;
+
+  while (bb.hasRemaining()) {
+    if(useGrayScale){
+      // read 8-bit pixel data
+      byte pixelValue = bb.get();
+
+      // set pixel color
+      myImage.pixels[i++] = color(Byte.toUnsignedInt(pixelValue));
+    } else {
+      // read 16-bit pixel data
+      int[] rgbValues = convertRGB565ToRGB888(bb.getShort());
+
+      // set pixel RGB color
+      myImage.pixels[i++] = color(rgbValues[0], rgbValues[1], rgbValues[2]);
+    }       
+  }
+  
+  myImage.updatePixels();
+  
+  // Ensures that the new image data is drawn in the next draw loop
+  shouldRedraw = true;
+  
+  // Let the Arduino sketch know we received all pixels
+  // and are ready for the next frame
+  myPort.write(1);
+}
+
+void keyPressed() {
+  if (key == ' ') {
+    useGrayScale = !useGrayScale; // change boolean value of greyscale when space is pressed
+  }
+}
diff --git a/libraries/Camera/library.properties b/libraries/Camera/library.properties
new file mode 100644
index 00000000..f46e9349
--- /dev/null
+++ b/libraries/Camera/library.properties
@@ -0,0 +1,9 @@
+name=Camera
+version=1.0
+author=Arduino
+maintainer=Arduino <info@arduino.cc>
+sentence=Library to capture pixels from supported cameras on Arduino boards.
+paragraph=The Arduino camera library is a C++ library designed to capture frames from cameras on supported Arduino products.
+category=Device Control
+url=https://github.com/arduino/ArduinoCore-zephyr/tree/master/libraries/Camera
+architectures=zephyr,zephyr_portenta,zephyr_nicla,zephyr_giga
diff --git a/libraries/Camera/src/camera.cpp b/libraries/Camera/src/camera.cpp
new file mode 100644
index 00000000..af00dbfb
--- /dev/null
+++ b/libraries/Camera/src/camera.cpp
@@ -0,0 +1,170 @@
+/*
+ * Copyright 2025 Arduino SA
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ * Camera driver.
+ */
+#include "Arduino.h"
+#include "camera.h"
+
+#include <zephyr/kernel.h>
+#include <zephyr/device.h>
+#include <zephyr/drivers/video.h>
+#include <zephyr/drivers/video-controls.h>
+
+FrameBuffer::FrameBuffer() : vbuf(NULL) {
+
+}
+
+uint32_t FrameBuffer::getBufferSize() {
+    if (this->vbuf) {
+        return this->vbuf->bytesused;
+    }
+}
+
+uint8_t* FrameBuffer::getBuffer() {
+    if (this->vbuf) {
+        return this->vbuf->buffer;
+    }
+}
+
+Camera::Camera() : vdev(NULL), byte_swap(false), yuv_to_gray(false) {
+	for (size_t i = 0; i < ARRAY_SIZE(this->vbuf); i++) {
+		this->vbuf[i] = NULL;
+    }
+}
+
+bool Camera::begin(uint32_t width, uint32_t height, uint32_t pixformat, bool byte_swap) {
+    #if DT_HAS_CHOSEN(zephyr_camera)
+    this->vdev = DEVICE_DT_GET(DT_CHOSEN(zephyr_camera));
+    #endif
+
+    if (!this->vdev || !device_is_ready(this->vdev)) {
+        return false;
+    }
+
+    switch (pixformat) {
+        case CAMERA_RGB565:
+            this->byte_swap = byte_swap;
+            pixformat = VIDEO_PIX_FMT_RGB565;
+            break;
+        case CAMERA_GRAYSCALE:
+            // There's no support for mono sensors.
+            this->yuv_to_gray = true;
+            pixformat = VIDEO_PIX_FMT_YUYV;
+            break;
+        default:
+            break;
+    }
+
+    // Get capabilities
+    struct video_caps caps = {0};
+    if (video_get_caps(this->vdev, VIDEO_EP_OUT, &caps)) {
+        return false;
+    }
+
+    for (size_t i=0; caps.format_caps[i].pixelformat != NULL; i++) {
+        const struct video_format_cap *fcap = &caps.format_caps[i];
+        if (fcap->width_min == width &&
+            fcap->height_min == height &&
+            fcap->pixelformat == pixformat) {
+            break;
+        }
+        if (caps.format_caps[i+1].pixelformat == NULL) {
+            Serial.println("The specified format is not supported");
+            return false;
+        }
+    }
+
+    // Set format.
+    static struct video_format fmt = {
+        .pixelformat = pixformat,
+        .width = width,
+        .height = height,
+        .pitch = width * 2,
+    };
+
+	if (video_set_format(this->vdev, VIDEO_EP_OUT, &fmt)) {
+        Serial.println("Failed to set video format");
+		return false;
+	}
+
+	// Allocate video buffers.
+	for (size_t i = 0; i < ARRAY_SIZE(this->vbuf); i++) {
+		this->vbuf[i] = video_buffer_aligned_alloc(fmt.pitch * fmt.height,
+                                                   CONFIG_VIDEO_BUFFER_POOL_ALIGN,
+                                                   K_FOREVER);
+		if (this->vbuf[i] == NULL) {
+            Serial.println("Failed to allocate video buffers");
+			return false;
+		}
+		video_enqueue(this->vdev, VIDEO_EP_OUT, this->vbuf[i]);
+	}
+
+	// Start video capture
+	if (video_stream_start(this->vdev)) {
+        Serial.println("Failed to start capture");
+		return false;
+	}
+
+    return true;
+}
+
+bool Camera::grabFrame(FrameBuffer &fb, uint32_t timeout) {
+    if (this->vdev == NULL) {
+        return false;
+    }
+
+    if (video_dequeue(this->vdev, VIDEO_EP_OUT, &fb.vbuf, K_MSEC(timeout))) {
+        return false;
+    }
+
+    if (this->byte_swap) {
+        uint16_t *pixels = (uint16_t *) fb.vbuf->buffer;
+        for (size_t i=0; i<fb.vbuf->bytesused / 2; i++) {
+            pixels[i] = __REVSH(pixels[i]);
+        }
+    }
+
+    if (this->yuv_to_gray) {
+        uint8_t *pixels = (uint8_t *) fb.vbuf->buffer;
+        for (size_t i=0; i<fb.vbuf->bytesused / 2; i++) {
+            pixels[i] = pixels[i*2];
+        }
+        fb.vbuf->bytesused /= 2;
+    }
+
+    return true;
+}
+
+bool Camera::releaseFrame(FrameBuffer &fb) {
+    if (this->vdev == NULL) {
+        return false;
+    }
+
+    if (video_enqueue(this->vdev, VIDEO_EP_OUT, fb.vbuf)) {
+        return false;
+	}
+
+    return true;
+}
+
+bool Camera::setVerticalFlip(bool flip_enable) {
+    return video_set_ctrl(this->vdev, VIDEO_CID_VFLIP, (void *) flip_enable) == 0;
+}
+
+bool Camera::setHorizontalMirror(bool mirror_enable) {
+    return video_set_ctrl(this->vdev, VIDEO_CID_HFLIP, (void *) mirror_enable) == 0;
+}
diff --git a/libraries/Camera/src/camera.h b/libraries/Camera/src/camera.h
new file mode 100644
index 00000000..c456c5ff
--- /dev/null
+++ b/libraries/Camera/src/camera.h
@@ -0,0 +1,127 @@
+/*
+ * Copyright 2025 Arduino SA
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#ifndef __CAMERA_H__
+#define __CAMERA_H__
+/** 
+ * @enum CameraPixelFormat
+ * @brief Camera pixel format enumeration.
+ * 
+ * The different formats use different numbers of bits per pixel:
+ * - Grayscale (8-bit)
+ * - RGB565 (16-bit)
+ */
+enum CameraPixelFormat {
+    CAMERA_RGB565,    /**< RGB565 format (16-bit). */
+    CAMERA_GRAYSCALE, /**< Grayscale format (8-bit). */
+};
+
+/**
+ * @class FrameBuffer
+ * @brief Frame buffer class for storing captured frames.
+ */
+class FrameBuffer {
+    private:
+        struct video_buffer *vbuf;
+
+    public:
+        /**
+         * @brief Construct a new FrameBuffer object.
+         */
+        FrameBuffer();
+
+        /**
+         * @brief Get the buffer size in bytes.
+         * @return uint32_t The buffer size in bytes.
+         */
+        uint32_t getBufferSize();
+
+        /**
+         * @brief Get a pointer to the frame buffer.
+         * 
+         * This can be used to read the pixels from the frame buffer.
+         * For example, to print all pixels to the serial monitor as hex values.
+         * 
+         * @return uint8_t* Pointer to the frame buffer.
+         */
+        uint8_t* getBuffer();
+    friend class Camera;
+};
+
+/**
+ * @class Camera
+ * @brief The main class for controlling a camera.
+ */
+class Camera {
+    private:
+        bool byte_swap;
+        bool yuv_to_gray;
+        const struct device *vdev;
+        struct video_buffer *vbuf[CONFIG_VIDEO_BUFFER_POOL_NUM_MAX];
+
+    public:
+        /**
+         * @brief Construct a new Camera object.
+         */
+        Camera();
+
+        /**
+         * @brief Initialize the camera.
+         * 
+         * @param width Frame width in pixels.
+         * @param height Frame height in pixels.
+         * @param pixformat Initial pixel format (default: CAMERA_RGB565).
+         * @param byte_swap Enable byte swapping (default: false).
+         * @return true if the camera is successfully initialized, otherwise false.
+         */
+        bool begin(uint32_t width, uint32_t height, uint32_t pixformat = CAMERA_RGB565, bool byte_swap = false);
+
+        /**
+         * @brief Capture a frame.
+         * 
+         * @param fb Reference to a FrameBuffer object to store the frame data.
+         * @param timeout Time in milliseconds to wait for a frame (default: 5000).
+         * @return true if the frame is successfully captured, otherwise false.
+         */
+        bool grabFrame(FrameBuffer &fb, uint32_t timeout = 5000);
+
+        /**
+         * @brief Release a frame buffer.
+         * 
+         * @param fb Reference to a FrameBuffer object to release.
+         * @return true if the frame buffer is successfully released, otherwise false.
+         */
+        bool releaseFrame(FrameBuffer &fb);
+
+        /**
+         * @brief Flip the camera image vertically.
+         * 
+         * @param flip_enable Set to true to enable vertical flip, false to disable.
+         * @return true on success, false on failure.
+         */
+        bool setVerticalFlip(bool flip_enable);
+
+        /**
+         * @brief Mirror the camera image horizontally.
+         * 
+         * @param mirror_enable Set to true to enable horizontal mirror, false to disable.
+         * @return true on success, false on failure.
+         */
+        bool setHorizontalMirror(bool mirror_enable);
+};
+
+#endif // __CAMERA_H__
diff --git a/loader/boards/arduino_giga_r1_m7.conf b/loader/boards/arduino_giga_r1_m7.conf
index ac1366a3..ab745912 100644
--- a/loader/boards/arduino_giga_r1_m7.conf
+++ b/loader/boards/arduino_giga_r1_m7.conf
@@ -10,6 +10,7 @@ CONFIG_UART_LINE_CTRL=y
 CONFIG_CDC_ACM_DTE_RATE_CALLBACK_SUPPORT=y
 
 CONFIG_LLEXT_STORAGE_WRITABLE=n
+CONFIG_SHARED_MULTI_HEAP=y
 CONFIG_HEAP_MEM_POOL_SIZE=2048
 CONFIG_SHELL_STACK_SIZE=32768
 CONFIG_MAIN_STACK_SIZE=32768
@@ -26,10 +27,15 @@ CONFIG_MEMC=y
 CONFIG_SPI_ASYNC=y
 CONFIG_SPI_STM32_INTERRUPT=y
 
-#CONFIG_VIDEO=y
-CONFIG_VIDEO_STM32_DCMI=y
-CONFIG_VIDEO_BUFFER_POOL_NUM_MAX=1
-CONFIG_VIDEO_BUFFER_POOL_SZ_MAX=160000
-
 CONFIG_ENTROPY_GENERATOR=y
-CONFIG_TEST_RANDOM_GENERATOR=y
\ No newline at end of file
+CONFIG_TEST_RANDOM_GENERATOR=y
+
+CONFIG_VIDEO=y
+CONFIG_VIDEO_LOG_LEVEL_DBG=y
+CONFIG_VIDEO_STM32_DCMI=y
+CONFIG_VIDEO_BUFFER_POOL_NUM_MAX=3
+CONFIG_VIDEO_BUFFER_POOL_SZ_MAX=614400
+CONFIG_VIDEO_BUFFER_POOL_ALIGN=32
+CONFIG_VIDEO_BUFFER_USE_SHARED_MULTI_HEAP=y
+CONFIG_VIDEO_BUFFER_SMH_ATTRIBUTE=2
+CONFIG_VIDEO_GC2145=y
diff --git a/loader/boards/arduino_giga_r1_m7.overlay b/loader/boards/arduino_giga_r1_m7.overlay
index 10c3caa8..076a99c9 100644
--- a/loader/boards/arduino_giga_r1_m7.overlay
+++ b/loader/boards/arduino_giga_r1_m7.overlay
@@ -29,14 +29,14 @@
 
 &i2c4 {
 	status = "okay";
-	ov7670: ov7670@21 {
-		compatible = "ovti,ov7670";
-		reg = <0x21>;
+	gc2145: gc2145@3c {
+		compatible = "galaxycore,gc2145";
+		reg = <0x3c>;
 		reset-gpios = <&gpiod 4 GPIO_ACTIVE_LOW>;
 		pwdn-gpios = <&gpioa 1 GPIO_ACTIVE_LOW>;
 
 		port {
-			ov7670_ep_out: endpoint {
+			gc2145_ep_out: endpoint {
 				remote-endpoint = <&dcmi_ep_in>;
 			};
 		};
@@ -59,7 +59,7 @@
 
 &timers1 {
 	status = "okay";
-	st,prescaler = <4>;
+	st,prescaler = <0>;
 
 	pwm1: pwm {
 		status = "okay";
@@ -144,7 +144,7 @@
 
 &dcmi {
 	status = "okay";
-	sensor = <&ov7670>;
+	sensor = <&gc2145>;
 	/* ext-sdram = <&sdram1>; */
 	pinctrl-0 = <&dcmi_hsync_ph8 &dcmi_pixclk_pa6 &dcmi_vsync_pi5
 				&dcmi_d0_ph9 &dcmi_d1_ph10 &dcmi_d2_ph11 &dcmi_d3_pg11
@@ -156,12 +156,12 @@
 	pixelclk-active = <0>;
 	capture-rate = <1>;
 	dmas = <&dma1 0 75 (STM32_DMA_PERIPH_TO_MEMORY | STM32_DMA_PERIPH_NO_INC |
-			STM32_DMA_MEM_INC | STM32_DMA_PERIPH_8BITS | STM32_DMA_MEM_32BITS |
+			STM32_DMA_MEM_INC | STM32_DMA_PERIPH_32BITS | STM32_DMA_MEM_32BITS |
 			STM32_DMA_PRIORITY_HIGH) STM32_DMA_FIFO_1_4>;
 
 	port {
 		dcmi_ep_in: endpoint {
-			remote-endpoint = <&ov7670_ep_out>;
+			remote-endpoint = <&gc2145_ep_out>;
 		};
 	};
 };
@@ -318,6 +318,7 @@
 /{
 	chosen {
 		zephyr,camera = &dcmi;
+		/* zephyr,console = &cdc_acm_uart0; */
 	};
 
 	/* used to overcome problems with _C analog pins */
@@ -508,7 +509,7 @@
 		cdc-acm = <&cdc_acm_uart0>;
 		i2cs = <&i2c2>, <&i2c4>, <&i2c1>;
 		spis = <&spi1>, <&spi5>;
-		pwms = <&pwm1 3 PWM_HZ(6000000) PWM_POLARITY_NORMAL>,
+		pwms = <&pwm1 3 PWM_HZ(12000000) PWM_POLARITY_NORMAL>,
 			   <&pwm2 4 PWM_HZ(500) PWM_POLARITY_NORMAL>,
 			   <&pwm2 3 PWM_HZ(500) PWM_POLARITY_NORMAL>,
 			   <&pwm8 1 PWM_HZ(500) PWM_POLARITY_NORMAL>,
diff --git a/loader/fixups.c b/loader/fixups.c
index 82a6c54a..aca88c15 100644
--- a/loader/fixups.c
+++ b/loader/fixups.c
@@ -70,4 +70,52 @@ int camera_ext_clock_enable(void)
 
 SYS_INIT(camera_ext_clock_enable, POST_KERNEL, CONFIG_CLOCK_CONTROL_PWM_INIT_PRIORITY);
 
-#endif
\ No newline at end of file
+#endif
+
+#if defined(CONFIG_SHARED_MULTI_HEAP)
+#include <zephyr/kernel.h>
+#include <zephyr/devicetree.h>
+#include <zephyr/multi_heap/shared_multi_heap.h>
+
+struct memory_region_t {
+	uintptr_t dt_addr;
+	size_t dt_size;
+	const char *dt_name;
+};
+
+#define _BUILD_MEM_REGION(node_id)      \
+	{ .dt_addr = DT_REG_ADDR(node_id),  \
+      .dt_size = DT_REG_SIZE(node_id),  \
+      .dt_name = DT_PROP(node_id, zephyr_memory_region) \
+    },
+
+int smh_init(void)
+{
+    int ret = 0;
+    ret = shared_multi_heap_pool_init();
+    if (ret != 0) {
+        return ret;
+    }
+
+    const struct memory_region_t regions[] = {
+        DT_FOREACH_STATUS_OKAY(zephyr_memory_region, _BUILD_MEM_REGION)
+    };
+
+    for (size_t i=0; i<ARRAY_SIZE(regions); i++) {
+        if (!strncmp("SDRAM", regions[i].dt_name, 5)) {
+            struct shared_multi_heap_region smh_sdram = {
+                .addr = regions[i].dt_addr,
+                .size = regions[i].dt_size,
+                .attr = SMH_REG_ATTR_EXTERNAL,
+            };
+            ret = shared_multi_heap_add(&smh_sdram, NULL);
+            if (ret != 0) {
+                return ret;
+            }
+        }
+    }
+	return 0;
+}
+
+SYS_INIT(smh_init, POST_KERNEL, CONFIG_CLOCK_CONTROL_PWM_INIT_PRIORITY);
+#endif
diff --git a/loader/llext_exports.c b/loader/llext_exports.c
index 618e6538..f427ccbc 100644
--- a/loader/llext_exports.c
+++ b/loader/llext_exports.c
@@ -103,6 +103,11 @@ FORCE_EXPORT_SYM(video_buffer_alloc);
 FORCE_EXPORT_SYM(video_buffer_release);
 #endif
 
+#if defined(CONFIG_SHARED_MULTI_HEAP)
+FORCE_EXPORT_SYM(shared_multi_heap_aligned_alloc);
+FORCE_EXPORT_SYM(shared_multi_heap_free);
+#endif
+
 #if defined(CONFIG_NET_SOCKETS)
 FORCE_EXPORT_SYM(getaddrinfo);
 FORCE_EXPORT_SYM(socket);
@@ -176,4 +181,4 @@ FORCE_EXPORT_SYM(__aeabi_f2d);
 FORCE_EXPORT_SYM(__aeabi_idivmod);
 FORCE_EXPORT_SYM(__aeabi_ldivmod);
 FORCE_EXPORT_SYM(__aeabi_ul2f);
-FORCE_EXPORT_SYM(__cxa_pure_virtual);
\ No newline at end of file
+FORCE_EXPORT_SYM(__cxa_pure_virtual);