- Following this tutorial.
FROM osrf/ros:noetic-desktop-full
ARG USER=user
ARG DEBIAN_FRONTEND=noninteractive
# Install ROS Noetic
RUN apt-get update && apt-get install -y \
iputils-ping \
terminator \
python3-pip git \
ros-noetic-moveit ros-noetic-ros-controllers ros-noetic-gazebo-ros-control \
ros-noetic-rosserial ros-noetic-rosserial-arduino \
ros-noetic-rqt ros-noetic-rqt-common-plugins \
ros-noetic-roboticsgroup-upatras-gazebo-plugins ros-noetic-actionlib-tools && \
rm -rf /var/lib/apt/lists/*
# Install Flask and Ask SDK
RUN pip install flask flask-ask-sdk ask-sdk
# Source ROS & Workspace to .bashrc
COPY bashrc /root/.bashrc
# Run the setup script to install the ROS Workspace
COPY setup.sh /setup.sh
ENTRYPOINT [ "/bin/bash", "/setup.sh" ]
# Run any extra commands we might want to pass in
CMD [ "bash" ]
# Set the working directory
WORKDIR /home/usr- Start Docker on your windows PC
- Open a terminal and fun the following:
docker run -it --rm --user=$($USER):$($USER) -e DISPLAY=host.docker.internal:0.0 --volume="/etc/group:/etc/group:ro" --volume="/etc/passwd:/etc/passwd:ro" --volume="/etc/shadow:/etc/shadow:ro" --volume="/etc/sudoers.d:/etc/sudoers.d:ro" --net host -v /home:/home -v C:\Volumes:/home/usr/ ros-noetic-containerMake sure you have a directory called
\VolumesatC:\Volumes, or change the path in the run command:-v C:\Volumes:/home/usr/
- On successful launch, we need to make sure we are sourcing ROS whenever we enter our ROS container:
echo source "/opt/ros/noetic/setup.bash" >> ~/.bashrc && source ~/.bashrcYou have to rebuild everytime you add command to the RUN function:
cd path/to/dockerfile
docker build . -t [container name]so for example:
cd ~/Documents/docker_ros_noetic
docker build . -t ros-noetic-containerRebuilding takes about 10 minutes, so be strategic.
- The XServer file
config.xlaunchlaunches automatically on startup.
- You can verify by finding the
Xin the system tray, which should read outmimus:0:0on hover.
TROUBLESHOOTING: Also you can click onC:\Users\mimus-cnk\Dropbox\mimus_cnk_project\docker_ros_noetic\config.xlaunchto run in background.
udp_sender in docker needs to be explictly set host to ipv4 address of the PC. For example, setting local host as "127.0.0.1" doesn't work, but "192.168.1.100" does.
udp_receiver in docker: STILL NOT WORKING without read/write to file.
- If I try to explicitly bind the socket to
192.168.1.100, I get the following error:
self.udp_receiver = UDPReceiveThread(host=hostname, port=port, filename='joint_positions.json')
File "/home/usr/exhibit_manager/udp_receive_thread.py", line 19, in __init__
self.sock.bind((self.host, self.port))
OSError: [Errno 99] Cannot assign requested address
- If bind the socket to all interfaces, nothing is received.
self.sock.bind(('', self.port)) # Bind to all interfaces
This now happens automatically in the startup.sh script that docker runs. It checks for the ros workspace, and then downloads and installs everything if it's not there (should only need to do once).
Volumes
└── /catkin_ws
└── /src
└── /khi_robotics
cd Volumes/catkin_ws
catkin_make
catkin_make installThen Source the package's setup.bash script in ~/.bashrc
echo 'source /home/usr/catkin_ws/devel/setup.bash' >> ~/.bashrc && source ~/.bashrc- Put the Control Box and Teach Pendant into
REPEATmode. - Verify your PC can communicate with the robot with a ping test:
ping 192.168.10.25-
From the docker terminal, launch
terminatorfor all our ROS needs: -
In terminator, run the command:
roscore -
Make a new terminal in terminator, change to the
catkin_wsdirectory, and run the following commands:
roslaunch khi_robot_bringup rs007l_bringup.launch ip:=192.168.10.25roslaunch khi_robot_bringup rs007l_bringup.launch simulation:=trueroslaunch khi_rs_gazebo rs007l_world.launch- Kill any running
roscoreinstances, then run:
roslaunch khi_rs007l_moveit_config moveit_planning_execution.launch RViz will get stuck
Initializing...ifroscoreis running.
Based on source code of
rqt_joint_trajectory_controller.
rosrun rqt_joint_trajectory_controller rqt_joint_trajectory_controllerimport rospy
import math
import signal
import sys
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from sensor_msgs.msg import JointState
from khi_robot.srv import KhiRobotCmd
class JointStateReader:
def __init__(self):
self.joint_names = ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6']
self.joint_positions = {name: None for name in self.joint_names}
self.sub = rospy.Subscriber('/joint_states', JointState, self.joint_state_callback)
def joint_state_callback(self, msg):
for name, position in zip(msg.name, msg.position):
if name in self.joint_names:
self.joint_positions[name] = position
def get_joint_positions(self):
while not all(pos is not None for pos in self.joint_positions.values()):
rospy.sleep(0.1)
return self.joint_positions
class JointPositionPublisher:
def __init__(self):
rospy.init_node('joint_position_publisher', anonymous=True)
self.joint_state_reader = JointStateReader()
rospy.sleep(1) # Give some time to receive the messages
self.initial_positions = list(self.joint_state_reader.get_joint_positions().values())
print(f"\tInitial Positions: {self.initial_positions}")
self.joint_positions = list(self.joint_state_reader.get_joint_positions().values())
self.pub = rospy.Publisher('/rs007l_arm_controller/command', JointTrajectory, queue_size=10)
self.joint_names = ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6']
self.start_time = rospy.Time.now().to_sec()
self.is_running = True
self.dt = 1.0/60.0 # 60 Hz
self.rate = rospy.Rate(1.0/self.dt)
# Register signal handlers
signal.signal(signal.SIGINT, self.shutdown)
signal.signal(signal.SIGTERM, self.shutdown)
def publish_joint_positions(self):
while not rospy.is_shutdown() and self.is_running:
traj = JointTrajectory()
traj.joint_names = self.joint_names
point = JointTrajectoryPoint()
current_time = rospy.Time.now().to_sec()
joint3_position = self.initial_positions[2] + 0.5 * math.sin(2 * math.pi * 0.05 * (current_time - self.start_time))
joint4_position = self.initial_positions[3] + 0.5 * math.sin(2 * math.pi * 0.1 * (current_time - self.start_time))
self.joint_positions[2] = joint3_position
self.joint_positions[3] = joint4_position
point.positions = self.joint_positions
point.time_from_start = rospy.Duration(self.dt)
traj.points.append(point)
self.pub.publish(traj)
self.rate.sleep()
def shutdown(self, signum, frame):
rospy.loginfo("\tShutting down. Returning to initial position...")
self.is_running = False
# Send the robot to the initial joint positions
duration = 5.0
traj = JointTrajectory()
traj.joint_names = self.joint_names
point = JointTrajectoryPoint()
point.positions = self.initial_positions
point.time_from_start = rospy.Duration(duration)
traj.points.append(point)
self.pub.publish(traj)
rospy.sleep(duration) # Allow time for the robot to move to the initial positions
rospy.signal_shutdown("Node shutdown gracefully")
return
if __name__ == '__main__':
try:
joint_position_publisher = JointPositionPublisher()
joint_position_publisher.publish_joint_positions()
except rospy.ROSInterruptException:
pass

