Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions subt/docker/rospy/Dockerfile
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
FROM ubuntu:20.04
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Are you sure, that ROS for Ubuntu 18 (Melodic) and Ubuntu 20 (Noetic) are compatible?! (for some older versions this used to be headache)


RUN apt-get update \
&& DEBIAN_FRONTEND=noninteractive apt-get install -y --no-install-recommends \
python3-rospy \
python3-std-srvs \
&& apt-get clean

ADD subt/docker/rospy/cmd.py .

ENTRYPOINT []

CMD [ "/usr/bin/python3" , "cmd.py" ]
#CMD [ "/bin/bash" ]
43 changes: 43 additions & 0 deletions subt/docker/rospy/cmd.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@

import time

import rospy
from rospy.impl import rosout
from std_srvs.srv import SetBool


def main():
rospy.init_node('python3-test', log_level=rospy.DEBUG)
print("Waiting for /rosout logger")
while rosout._rosout_pub.get_num_connections() == 0:
time.sleep(0.2)
rospy.loginfo("python3 client running")

params = rospy.get_param_names()
for name in params:
value = rospy.get_param(name)
rospy.loginfo(f"{name}: {str(value)}")

# we need these services
rospy.loginfo("waiting for /subt/start and /subt/finish")
rospy.wait_for_service('/subt/start')
rospy.wait_for_service('/subt/finish')

# if clock is not ticking, service /subt/start will return with error
rospy.loginfo("waiting for clock")
rospy.sleep(2)
rospy.loginfo(repr(rospy.get_rostime()))

try:
subt_start = rospy.ServiceProxy('/subt/start', SetBool)
ret = subt_start(True)
rospy.loginfo("/subt/start: {0}".format(ret.success))

finally:
subt_finish = rospy.ServiceProxy('/subt/finish', SetBool)
ret = subt_finish(True)
rospy.loginfo("/subt/finish: {0}".format(ret.success))


if __name__ == "__main__":
main()