Skip to content
4 changes: 4 additions & 0 deletions NOTICE
Original file line number Diff line number Diff line change
Expand Up @@ -31,3 +31,7 @@ Robert Bosch GmbH

Boston Engineering
Connor Lansdale <[email protected]>

Dor Ben Harush
Dor Ben Harush <[email protected]>

51 changes: 51 additions & 0 deletions config/freertos/esp32/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,54 @@
- You can run idf targets like `menuconfig` or `monitor` by specifing the target as an argument to the `build_firmware.sh` script
- The GPIO pins for the configured serial port can be set with `menuconfig` (see `micro-ROS Transport Settings` menu)
- ESP32 only runs in singlecore mode (`CONFIG_FREERTOS_UNICORE=y` setting)


# Notes for ESP32-CAMERA

- SPIRAM is requierd only for ESP32-CAMERA and can cause a fatal error in ESP32 (Enable in `menuconfig Component config > ESP32-specific` OR add `CONFIG_ESP32_SPIRAM_SUPPORT=y` to `sdkconfig.defaults` file).
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Regarding this, is possible to explain it a README.md inside the freertos_apps app folder?

- Make sure that `rtc_gpio_desc` array is supported in `menuconfig: Component config > Driver configurations > RTCIO configuration` (set to TRUE)
OR write this line `CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC=y` to `sdk.defaults`.
- Choose your camera pins configuration in `menuconfig Camera configuration > Camera pins`. (`BOARD_ESP32CAM_AITHINKER` is default).
- In order to view the images you will need to create a cv_bridge:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would like to see this Python app as a .py file included in the freertos_apps app specific folder

```
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import CompressedImage
import cv2
import numpy as np
class MinimalSubscriber(Node):
def __init__(self, ):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(CompressedImage, 'freertos_picture_publisher', self.listener_callback, 10)
self.subscription # prevent unused variable warning
self.bridge = CvBridge()
def listener_callback(self, image_message):
self.get_logger().info('recieved an image')
#recieve image and co nvert to cv2 image
cv2.imshow('esp32_image', self.cv_image)
cv2.waitKey(3)
def main(args=None):
rclpy.init(args=args)
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
4 changes: 4 additions & 0 deletions config/freertos/esp32/create.sh
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@ pushd $FW_TARGETDIR >/dev/null

pushd toolchain >/dev/null
git clone -b v4.1 --recursive https://github.com/espressif/esp-idf.git
pushd esp-idf/components
#add the esp32-camera repository to the components directory
git clone https://github.com/espressif/esp32-camera.git
popd

mkdir espressif
export IDF_TOOLS_PATH=$(pwd)/espressif
Expand Down