Skip to content
This repository has been archived by the owner on Dec 4, 2024. It is now read-only.

Commit

Permalink
pozyx test and camera streaming progress
Browse files Browse the repository at this point in the history
  • Loading branch information
manglemix committed Sep 20, 2023
1 parent f2c263d commit fcccefc
Show file tree
Hide file tree
Showing 14 changed files with 253 additions and 8 deletions.
6 changes: 6 additions & 0 deletions lunadev/luna.dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -61,5 +61,11 @@ RUN apt-get install -y --no-install-recommends \
# Install VNC and socat
RUN apt-get install -y x11vnc socat xvfb

# Configure git
RUN git config pull.rebase false

# Install ffmpeg
RUN apt install ffmpeg

COPY base_bashrc_append.sh /bashrc_append
RUN ["/bin/bash", "-c", "cat /bashrc_append >> /root/.bashrc && rm /bashrc_append"]
Empty file added src/camera/camera/__init__.py
Empty file.
99 changes: 99 additions & 0 deletions src/camera/camera/camera_compress.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
import rclpy
from rclpy.node import Node
import subprocess
from sensor_msgs.msg import Image
from global_msgs.msg import CompressedImagePacket
from threading import Thread
from time import time


class CameraCompress(Node):
def __init__(self):
super().__init__("camera_compress")

self.target_fps = 10
self.ffmpeg = subprocess.Popen(
[
"ffmpeg",
"-f", "rawvideo",
"-pix_fmt", "rgb24",
"-s", "1280x720",
"-r", "10",
"-i", "-",
"-c:v", "libvpx-vp9",
"-b:v", "1500k",
# "-g", "72",
"-f", "matroska", "-"
],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
)

self.camera_listener = self.create_subscription(
Image,
'/camera/color/image_raw',
self.camera_callback_callback,
10
)
self.compressed_pub = self.create_publisher(CompressedImagePacket, 'compressed_image', 10)

self.count = 0
self.probe_complete = False
self.last_processed_frame_time = 0

self.thr = Thread(target=self.read_stdout)
self.thr.start()

def read_stdout(self):
try:
while True:
data = self.ffmpeg.stdout.read(1024 * 8)

if len(data) == 0:
err = b""
while True:
packet = self.ffmpeg.stderr.read(1024)
if len(packet) == 0:
break
err += packet
raise Exception(err.decode())

self.compressed_pub.publish(CompressedImagePacket(data=data))
self.probe_complete = True

except BrokenPipeError:
# Error will be caught in camera callback
return

def camera_callback_callback(self, img: Image):
if self.probe_complete and time() - self.last_processed_frame_time < 1.0 / self.target_fps:
return
try:
i = 0
while i < len(img.data):
i += self.ffmpeg.stdin.write(bytes(img.data[i::]))

except BrokenPipeError:
err = b""
while True:
packet = self.ffmpeg.stderr.read(1024)
if len(packet) == 0:
break
err += packet
raise Exception(err.decode())


def main(args=None):
rclpy.init(args=args)

node = CameraCompress()

rclpy.spin(node)

node.destroy_node()
# rclpy.shutdown()


if __name__ == "__main__":
raise Exception("Please run from ROS 2")
21 changes: 21 additions & 0 deletions src/camera/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>camera</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">root</maintainer>
<license>TODO: License declaration</license>

<exec_depend>sensor_msgs</exec_depend>
<exec_depend>global_msgs</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file added src/camera/resource/camera
Empty file.
4 changes: 4 additions & 0 deletions src/camera/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/camera
[install]
install_scripts=$base/lib/camera
26 changes: 26 additions & 0 deletions src/camera/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
from setuptools import find_packages, setup

package_name = 'camera'

setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='root',
maintainer_email='[email protected]',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'compress = camera.camera_compress:main'
],
},
)
25 changes: 25 additions & 0 deletions src/camera/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
25 changes: 25 additions & 0 deletions src/camera/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
23 changes: 23 additions & 0 deletions src/camera/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'
1 change: 1 addition & 0 deletions src/global_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Steering.msg"
"action/SetArmAngle.action"
"msg/CompressedImagePacket.msg"
)

if(BUILD_TESTING)
Expand Down
1 change: 1 addition & 0 deletions src/global_msgs/msg/CompressedImagePacket.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
uint8[] data
14 changes: 6 additions & 8 deletions src/positioning/positioning/pozyx_localizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,17 +177,15 @@ def loop(self):
orientation=MsgQuaternion(x=orientation.x, y=orientation.y, z=orientation.z, w=orientation.w)
)

if status == POZYX_SUCCESS:
print(self.posAndOrientatonToString())
else:
if status != POZYX_SUCCESS:
statusString = "failure" if status == POZYX_FAILURE else "timeout"
print('Error: Do positioning failed due to ' + statusString)

def posAndOrientatonToString(self):
"""
Returning a string with the x,y,z coordinates of the position and the orientation.
"""
return 'Current position:\n ' + str(self.position) + '\nCurrent orientation\n ' + str(self.orientation) + '\n'
# def posAndOrientatonToString(self):
# """
# Returning a string with the x,y,z coordinates of the position and the orientation.
# """
# return 'Current position:\n ' + str(self.position) + '\nCurrent orientation\n ' + str(self.orientation) + '\n'


if __name__ == '__main__':
Expand Down
16 changes: 16 additions & 0 deletions src/telemetry/telemetry/telemetry.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
from rclpy.node import Node
from struct import Struct
from global_msgs.msg import Steering
from global_msgs.msg import CompressedImagePacket
from std_msgs.msg import Float32


Expand Down Expand Up @@ -35,6 +36,13 @@ def __init__(self, scheme: int):
self.arm_vel_pub = self.create_publisher(
Float32, 'target_arm_velocity', 10
)
self.camera_image_buffer = bytearray()
self.camera_listener = self.create_subscription(
CompressedImagePacket,
'compressed_image',
self.receive_image,
10
)

self.scheme = scheme
if scheme == ControlScheme.ARCHIMEDES:
Expand All @@ -48,6 +56,9 @@ def __init__(self, scheme: int):
self.thr = Thread(target=self.run)
self.thr.start()

def receive_image(self, img: CompressedImagePacket):
self.camera_image_buffer += img.data

def run(self):
logger = self.get_logger()
host = enet.Host(None, 1, 0, 0, 0)
Expand Down Expand Up @@ -108,6 +119,11 @@ def run(self):
logger.error("Host has returned an error! Restarting...")
break

peer.send(
Channels.CAMERA,
enet.Packet(self.camera_image_buffer, enet.PACKET_FLAG_UNSEQUENCED)
)

def on_receive(self, channel: int, data: bytes, peer) -> None:
logger = self.get_logger()

Expand Down

0 comments on commit fcccefc

Please sign in to comment.