Skip to content

Commit e4abead

Browse files
tylerjwMarqRazzsea-bassknorth55
authored
Prepare for World MoveIt Day 2023 - Port Isaac Sim tutorial to main (#688)
Co-authored-by: Marq Rasmussen <[email protected]> Co-authored-by: Sebastian Castro <[email protected]> Co-authored-by: Shingo Kitagawa <[email protected]>
1 parent a4fd1f3 commit e4abead

File tree

13 files changed

+1121
-5
lines changed

13 files changed

+1121
-5
lines changed

.dockerignore

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,11 @@
1-
_scripts/
2-
_static/
3-
_templates/
4-
.docker/
1+
__pycache__
2+
**/.git
3+
**/.github
4+
**/_scripts
5+
**/_static
6+
**/_templates
7+
**/build
8+
**/.vscode
9+
**/.docker
10+
*.md
11+
*.rst

CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,16 +52,18 @@ include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
5252
# add_subdirectory(doc/examples/tests)
5353
# add_subdirectory(doc/examples/trajopt_planner)
5454
# add_subdirectory(doc/examples/visualizing_collisions)
55+
5556
add_subdirectory(doc/examples/jupyter_notebook_prototyping)
5657
add_subdirectory(doc/examples/motion_planning_api)
5758
add_subdirectory(doc/examples/motion_planning_pipeline)
5859
add_subdirectory(doc/examples/motion_planning_python_api)
5960
add_subdirectory(doc/examples/move_group_interface)
6061
add_subdirectory(doc/examples/moveit_cpp)
61-
add_subdirectory(doc/examples/planning_scene_ros_api)
6262
add_subdirectory(doc/examples/planning_scene)
63+
add_subdirectory(doc/examples/planning_scene_ros_api)
6364
add_subdirectory(doc/examples/realtime_servo)
6465
add_subdirectory(doc/examples/robot_model_and_robot_state)
66+
add_subdirectory(doc/how_to_guides/isaac_panda)
6567
add_subdirectory(doc/how_to_guides/kinematics_cost_function)
6668
add_subdirectory(doc/how_to_guides/parallel_planning)
6769
add_subdirectory(doc/how_to_guides/persistent_scenes_and_states)

doc/how_to_guides/how_to_guides.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,3 +30,4 @@ Developing and Documenting MoveIt
3030
how_to_generate_api_doxygen_locally
3131
how_to_setup_docker_containers_in_ubuntu
3232
how_to_write_doxygen
33+
isaac_panda/isaac_panda_tutorial
Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
FROM osrf/ros:humble-desktop-jammy
2+
3+
SHELL ["/bin/bash", "-c", "-o", "pipefail"]
4+
5+
RUN echo "deb [trusted=yes] https://raw.githubusercontent.com/moveit/moveit2_packages/jammy-humble/ ./" \
6+
| sudo tee /etc/apt/sources.list.d/moveit_moveit2_packages.list
7+
RUN echo "yaml https://raw.githubusercontent.com/moveit/moveit2_packages/jammy-humble/local.yaml humble" \
8+
| sudo tee /etc/ros/rosdep/sources.list.d/1-moveit_moveit2_packages.list
9+
10+
# Bring the container up to date to get the latest ROS2 humble sync on 01/27/23
11+
# hadolint ignore=DL3008, DL3013
12+
RUN apt-get update && apt-get upgrade -y && rosdep update
13+
14+
# Install packages required to run the demo
15+
RUN apt-get install -y --no-install-recommends \
16+
ros-humble-moveit \
17+
ros-humble-moveit-resources
18+
19+
# Create Colcon workspace and clone the needed source code to run the demo
20+
RUN mkdir -p /root/isaac_moveit_tutorial_ws/src
21+
WORKDIR /root/isaac_moveit_tutorial_ws/src
22+
RUN git clone https://github.com/PickNikRobotics/topic_based_ros2_control.git
23+
COPY ./ moveit2_tutorials
24+
WORKDIR /root/isaac_moveit_tutorial_ws
25+
# hadolint ignore=SC1091
26+
RUN source /opt/ros/humble/setup.bash \
27+
&& apt-get update -y \
28+
&& rosdep install --from-paths src --ignore-src --rosdistro "$ROS_DISTRO" -y \
29+
&& rm -rf /var/lib/apt/lists/*
30+
31+
# Use Fast DDS as middleware and load the required config for NVIDIA Isaac Sim.
32+
ENV RMW_IMPLEMENTATION=rmw_fastrtps_cpp
33+
RUN mkdir -p /opt/.ros
34+
COPY ./doc/how_to_guides/isaac_panda/.docker/fastdds.xml /opt/.ros/fastdds.xml
35+
ENV FASTRTPS_DEFAULT_PROFILES_FILE=/opt/.ros/fastdds.xml
36+
37+
# Build the Colcon workspace for the user
38+
RUN source /opt/ros/humble/setup.bash && colcon build
39+
40+
# Set up the entrypoint for both container start and interactive terminals.
41+
COPY ./doc/how_to_guides/isaac_panda/.docker/ros_entrypoint.sh /opt/.ros/
42+
RUN echo "source /opt/.ros/ros_entrypoint.sh" >> ~/.bashrc
43+
ENTRYPOINT [ "/opt/.ros/ros_entrypoint.sh" ]
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
<?xml version="1.0" encoding="UTF-8" ?>
2+
<!--
3+
Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
4+
5+
NVIDIA CORPORATION and its licensors retain all intellectual property
6+
and proprietary rights in and to this software, related documentation
7+
and any modifications thereto. Any use, reproduction, disclosure or
8+
distribution of this software and related documentation without an express
9+
license agreement from NVIDIA CORPORATION is strictly prohibited.
10+
-->
11+
<license>NVIDIA Isaac ROS Software License</license>
12+
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
13+
<transport_descriptors>
14+
<transport_descriptor>
15+
<transport_id>UdpTransport</transport_id>
16+
<type>UDPv4</type>
17+
</transport_descriptor>
18+
</transport_descriptors>
19+
20+
<participant profile_name="udp_transport_profile" is_default_profile="true">
21+
<rtps>
22+
<userTransports>
23+
<transport_id>UdpTransport</transport_id>
24+
</userTransports>
25+
<useBuiltinTransports>false</useBuiltinTransports>
26+
</rtps>
27+
</participant>
28+
</profiles>
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
#!/bin/bash
2+
3+
# Source ROS 2 Humble
4+
source /opt/ros/humble/setup.bash
5+
echo "Sourced ROS 2 Humble"
6+
7+
# Source the base workspace, if built
8+
if [ -f /root/isaac_moveit_tutorial_ws/install/setup.bash ]
9+
then
10+
source /root/isaac_moveit_tutorial_ws/install/setup.bash
11+
echo "Sourced isaac_moveit_tutorial workspace"
12+
else
13+
echo "Please build the isaac_moveit_tutorial workspace with:"
14+
echo "colcon build"
15+
fi
16+
17+
# Execute the command passed into this entrypoint
18+
exec "$@"
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
install(DIRECTORY launch
2+
DESTINATION share/${PROJECT_NAME}
3+
)
4+
install(DIRECTORY config
5+
DESTINATION share/${PROJECT_NAME}
6+
)

0 commit comments

Comments
 (0)