Initial commit of ros_relay

This commit is contained in:
safy 2023-11-08 10:13:45 -04:00
commit 809499ecbd
14 changed files with 154 additions and 0 deletions

24
Dockerfile Normal file
View File

@ -0,0 +1,24 @@
FROM ros:melodic-ros-base
RUN apt-get update
RUN apt-get install ros-melodic-rosbridge-suite python3-pip ros-melodic-mavros-msgs -y
RUN pip3 install --upgrade pip setuptools
#RUN sh -c "curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh"
RUN pip3 install roslibpy pyyaml rospkg
RUN pip3 install git+https://github.com/DFKI-NI/rospy_message_converter
RUN bash -c "source /opt/ros/melodic/setup.bash \
&& mkdir -p /overlay_ws/src \
&& cd /overlay_ws \
&& catkin_make"
COPY ./ros_relay/ /overlay_ws/src/ros_relay/
WORKDIR /overlay_ws
RUN bash -c "source devel/setup.bash && catkin_make"
ENV PYTHONUNBUFFERED=1
CMD bash -c "source devel/setup.bash && rosrun ros_relay relay.py"

13
docker-compose.yaml Normal file
View File

@ -0,0 +1,13 @@
version: "3.3"
services:
ros_relay:
build: ./
network_mode: host
environment:
HOST: "192.168.1.89"
PORT: "9090"
TOPIC_PREFIX: "/spiri/aurelia/"
TOPICS: "/mavros/battery,/mavros/global_position/"
volumes:
- ./ros_relay/:/overlay_ws/src/ros_relay/

14
ros_relay/CMakeLists.txt Normal file
View File

@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(ros_relay)
find_package(catkin REQUIRED COMPONENTS
rospy
message_generation
std_msgs)
catkin_python_setup()
catkin_install_python(PROGRAMS
src/ros_relay/__init__.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}/ros_relay)
generate_messages(DEPENDENCIES std_msgs)

0
ros_relay/__init__.py Normal file
View File

View File

0
ros_relay/msg/.gitkeep Normal file
View File

0
ros_relay/nodes/.gitkeep Normal file
View File

20
ros_relay/package.xml Normal file
View File

@ -0,0 +1,20 @@
<?xml version="1.0"?>
<package>
<name>ros_relay</name>
<version>0.1.0</version>
<description>Relay ros topics to central rosbridge</description>
<maintainer email="alex.davies@spirirobotics.com">Alex Davies</maintainer>
<author email="alex.davies@spirirobotics.com">Alex Davies</author>
<license>Not open source</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>message_runtime</run_depend>
<run_depend>rospy</run_depend>
<run_depend>roslaunch</run_depend>
<run_depend>std_msgs</run_depend>
</package>

View File

70
ros_relay/scripts/relay.py Executable file
View File

@ -0,0 +1,70 @@
#!/usr/bin/env python3
import rospy
from std_msgs.msg import String
from importlib import import_module
from rospy_message_converter import message_converter
import json
import roslibpy
import os
rosbridge = roslibpy.Ros(host=os.environ['HOST'], port=int(os.environ['PORT']))
rosbridge.run()
def callback_battery(data):
print(data)
print("-------")
class GenericMessageSubscriber(object):
def __init__(self, topic_name, callback):
self._binary_sub = rospy.Subscriber(
topic_name, rospy.AnyMsg, self.generic_message_callback)
self._callback = callback
def generic_message_callback(self, data):
connection_header = data._connection_header['type'].split('/')
ros_pkg = connection_header[0] + '.msg'
msg_type = connection_header[1]
msg_class = getattr(import_module(ros_pkg), msg_type)
msg = msg_class().deserialize(data._buff)
self._callback(msg)
class GenericMessageRelay(object):
def __init__(self, topic_name,topic_prefix=""):
"""topic_prefix is what we prefix the topic with
at the other end
"""
self.topic_name=topic_name
self.topic_prefix=topic_prefix
self._binary_sub = rospy.Subscriber(
topic_name, rospy.AnyMsg, self.generic_message_callback)
self.talker=None
def _callback(self,data):
jdata = message_converter.convert_ros_message_to_dictionary(data)
print(jdata)
self.talker.publish(jdata)
def generic_message_callback(self, data):
connection_header = data._connection_header['type'].split('/')
if not self.talker:
self.talker = roslibpy.Topic(rosbridge,self.topic_prefix+self.topic_name,data._connection_header['type'])
ros_pkg = connection_header[0] + '.msg'
msg_type = connection_header[1]
msg_class = getattr(import_module(ros_pkg), msg_type)
msg = msg_class().deserialize(data._buff)
self._callback(msg)
def listener():
print("starting up")
rospy.init_node('relay', anonymous=True)
for topic in os.environ["TOPICS"].split(','):
GenericMessageRelay(topic,topic_prefix=os.environ["TOPIC_PREFIX"])
rospy.spin()
if __name__ == '__main__':
listener()

13
ros_relay/setup.py Normal file
View File

@ -0,0 +1,13 @@
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['ros_relay'],
package_dir={'': 'src'},
requires=['std_msgs', 'rospy']
)
setup(**setup_args)

View File

0
ros_relay/srv/.gitkeep Normal file
View File

0
ros_relay/urdf/.gitkeep Normal file
View File