Commit 8ceeb352 authored by Larkin Heintzman's avatar Larkin Heintzman

working drone image build

parent bdfe40fb
...@@ -5,7 +5,7 @@ FROM ${from} ...@@ -5,7 +5,7 @@ FROM ${from}
# python-catkin-tools \ # python-catkin-tools \
# && rm -rf /var/lib/apt/lists/* # && rm -rf /var/lib/apt/lists/*
RUN apt-get update && apt-get install -y python3-pip git ca-certificates RUN apt-get update && apt-get install -y python3-pip git ca-certificates
RUN apt-get update && apt-get install -y libsdl2-dev libusb-1.0-0-dev build-essential cmake gcc ffmpeg python3-opencv libavcodec-dev libavdevice-dev libavfilter-dev libavformat-dev libavresample-dev libavutil-dev libpostproc-dev libswresample-dev libswscale-dev RUN apt-get update && apt-get install -y libsdl2-dev libusb-1.0-0-dev build-essential cmake ffmpeg python3-opencv libavcodec-dev libavdevice-dev libavfilter-dev libavformat-dev libavresample-dev libavutil-dev libpostproc-dev libswresample-dev libswscale-dev
RUN apt-get update && apt-get install -y ros-noetic-tf RUN apt-get update && apt-get install -y ros-noetic-tf
RUN pip3 install git+https://github.com/catkin/catkin_tools.git RUN pip3 install git+https://github.com/catkin/catkin_tools.git
...@@ -51,7 +51,7 @@ RUN apt-get update && \ ...@@ -51,7 +51,7 @@ RUN apt-get update && \
# build ros package source # build ros package source
RUN catkin config \ RUN catkin config \
--extend /opt/ros/$ROS_DISTRO && \ --extend /opt/ros/$ROS_DISTRO && \
catkin build catkin build --cmake-args -DCMAKE_CXX_FLAGS="-std=c++17"
# \ # \
# roscpp_tutorials # roscpp_tutorials
......
...@@ -20,11 +20,13 @@ spec: ...@@ -20,11 +20,13 @@ spec:
node: drone node: drone
spec: spec:
containers: containers:
# The real node container - name: drone
- name: droneContainer
image: llh/drone:v0 image: llh/drone:v0
command: ["/bin/bash"] command: ["/bin/bash"]
args: ["-c", "source /opt/ros_ws/devel/setup.bash && /usr/local/bin/bashCheckRoscore.sh && rostopic pub -r 1 plathReady std_msgs/String 'ready'"] args: ["-c", "source /opt/ros_ws/devel/setup.bash && /usr/local/bin/bashCheckRoscore.sh && rostopic pub -r 1 plathReady std_msgs/String 'ready'"]
ports:
- containerPort: 11311
name: droneport
env: env:
- name: ROS_MASTER_URI - name: ROS_MASTER_URI
value: http://service-master:11311 value: http://service-master:11311
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment