Skip to content

Commit babf9a8

Browse files
authored
Merge branch 'main' into ch3/trajectory-cache-example
2 parents 0310059 + 97f2fd2 commit babf9a8

20 files changed

+795
-31
lines changed

.docker/Dockerfile

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,16 @@
11
# syntax = docker/dockerfile:1.3
22

33
ARG ROS_DISTRO=rolling
4+
ARG GZ_VERSION=harmonic
45

56
######################### Tutorial Image #################################################
67

78
FROM moveit/moveit2:${ROS_DISTRO}-source as tutorial_image
89

910
LABEL org.opencontainers.image.description "This container has working versions of the tutorials discussed here: https://moveit.picknik.ai/main/doc/tutorials/tutorials.html"
1011

12+
ARG GZ_VERSION
13+
1114
# Copy sources from docker context
1215
COPY . src/moveit2_tutorials
1316

@@ -45,6 +48,12 @@ COPY ./doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cp
4548
# Add the launch folder to the tutorial package and CMakeLists.txt
4649
COPY ./doc/tutorials/pick_and_place_with_moveit_task_constructor/launch src/mtc_tutorial/launch
4750

51+
# Install Gazebo, which is needed by some dependencies.
52+
RUN sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' && \
53+
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add - && \
54+
sudo apt update && \
55+
sudo apt-get install -y "gz-${GZ_VERSION}"
56+
4857
# Add install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) to CMakeLists.txt
4958
RUN sed -i "s|ament_package()|install(DIRECTORY launch DESTINATION share/\${PROJECT_NAME})\nament_package()|g" src/mtc_tutorial/CMakeLists.txt
5059
# Build the tutorials and set up the entrypoint/bashrc

.github/upstream.repos

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,12 @@ repositories:
1616
url: https://github.com/PickNikRobotics/rviz_visual_tools.git
1717
version: ros2
1818
# Remove ros2_kortex when rolling binaries are available.
19+
# Need to use this fork since ros2_kortex depends on Gazebo classic packages:
20+
# https://github.com/Kinovarobotics/ros2_kortex/issues/217
1921
ros2_kortex:
2022
type: git
21-
url: https://github.com/Kinovarobotics/ros2_kortex.git
22-
version: main
23+
url: https://github.com/sea-bass/ros2_kortex.git
24+
version: remove-gazebo-classic
2325
# Remove ros2_robotiq_gripper when rolling binaries are available.
2426
ros2_robotiq_gripper:
2527
type: git
@@ -30,3 +32,8 @@ repositories:
3032
type: git
3133
url: https://github.com/tylerjw/serial.git
3234
version: ros2
35+
# Doesn't seem to be available from binaries yet
36+
gz_ros2_control:
37+
type: git
38+
url: https://github.com/ros-controls/gz_ros2_control.git
39+
version: master

.github/workflows/deploy.yml

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,12 @@ jobs:
2222
- uses: actions/checkout@v4
2323

2424
- name: Install Python dependencies
25+
shell: bash
2526
run: |
2627
sudo apt-get update -y
27-
sudo apt-get install -y python3-pip
28+
sudo apt-get install -y python3-pip python3-venv
29+
python3 -m venv .venv
30+
source .venv/bin/activate
2831
pip3 install --upgrade --requirement requirements.txt
2932
3033
- name: Install doxygen and graphviz
@@ -39,6 +42,7 @@ jobs:
3942
run: |
4043
source /opt/ros/rolling/setup.bash
4144
source /root/ws_moveit/install/setup.bash
45+
source .venv/bin/activate
4246
./htmlproofer.sh
4347
4448
upload_site_artifacts:
@@ -58,9 +62,12 @@ jobs:
5862
- uses: actions/checkout@v4
5963

6064
- name: Install Python dependencies
65+
shell: bash
6166
run: |
6267
sudo apt-get update -y
63-
sudo apt-get install -y python3-pip
68+
sudo apt-get install -y python3-pip python3-venv
69+
python3 -m venv .venv
70+
source .venv/bin/activate
6471
pip3 install --upgrade --requirement requirements.txt
6572
6673
- name: Install doxygen and graphviz
@@ -71,13 +78,14 @@ jobs:
7178
run: |
7279
source /opt/ros/${{ matrix.rosdistro }}/setup.bash
7380
source /root/ws_moveit/install/setup.bash
81+
source .venv/bin/activate
7482
make generate_api_artifacts BRANCH=${{ matrix.branch }}
7583
7684
- name: Compress Artifact
7785
run: tar cvzf artifact.tar.gz --directory=build/html .
7886

7987
- name: Upload HTML Artifact
80-
uses: actions/upload-artifact@v3
88+
uses: actions/upload-artifact@v4
8189
with:
8290
name: '${{ matrix.branch }}_html_artifacts'
8391
path: artifact.tar.gz
@@ -109,7 +117,7 @@ jobs:
109117

110118
# TODO (peterdavidfagan): don't hardcode branches for downloads
111119
- name: Download Rolling Artifacts
112-
uses: actions/download-artifact@v3
120+
uses: actions/download-artifact@v4
113121
with:
114122
name: main_html_artifacts
115123
path: .
@@ -121,7 +129,7 @@ jobs:
121129
rm artifact.tar.gz
122130
123131
- name: Download Humble Artifacts
124-
uses: actions/download-artifact@v3
132+
uses: actions/download-artifact@v4
125133
with:
126134
name: humble_html_artifacts
127135
path: .

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,5 +7,6 @@ build
77
Gemfile
88
native_build
99
*.gdb
10+
.venv
1011
# For local rst builds
1112
_build/

build_locally.sh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ fi
4141
# Install dependencies, unless argument says to skip
4242
if ! have_noinstall "$@"; then
4343
sudo apt-get install -y doxygen graphviz
44-
pip3 install --user --upgrade -r requirements.txt
44+
pip3 install --upgrade -r requirements.txt
4545
fi
4646

4747
# A fresh build is required because changes to some components such as css files does not rebuilt currently

doc/examples/hybrid_planning/hybrid_planning_tutorial.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ To start the hybrid planning demo simply run: ::
3636

3737
You should see a similar behavior as in the example GIF above without the replanning.
3838

39-
To interact with the architecture you simply need to send a *Hybrid Planning Request* to an action server offered by the *Hybrid Planning Manager* as seen in the :moveit_codedir:`hybrid_planning_test_node <moveit_ros/hybrid_planning/test/hybrid_planning_demo_node.cpp#L245>`.
39+
To interact with the architecture you simply need to send a *Hybrid Planning Request* to an action server offered by the *Hybrid Planning Manager*.
4040

4141
Let's change this behavior such that the architecture replans the invalidated trajectory. To do so, just change the *planner_logic_plugin* by replacing the plugin name in the :moveit_codedir:`demo configuration <moveit_ros/hybrid_planning/test/config/hybrid_planning_manager.yaml>` with "moveit_hybrid_planning/ReplanInvalidatedTrajectory" and rebuild the package : ::
4242

doc/examples/setup_assistant/setup_assistant_tutorial.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -504,7 +504,7 @@ To build only the generated ``panda_moveit_config`` package and run the demo, fo
504504

505505
Start the MoveIt demo to interactively plan and execute motions for the robot in RViz. ::
506506

507-
ros2 launch moveit_resources_panda_moveit_config demo.launch.py
507+
ros2 launch panda_moveit_config demo.launch.py
508508

509509
Check out this `brief YouTube video <https://youtu.be/f__udZlnTdM>`_ for an example of how to
510510
command the robot to move to the pre-defined ``ready`` pose and execute ``open`` and ``close`` motions on the hand.

doc/how_to_contribute/how_to_contribute_to_site.rst

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,20 @@ Steps
4040
4141
2. Test for broken links
4242

43-
To test for broken links run this command:
43+
To test for broken links, run the ``htmlproofer`` script. Note that running this script may require you to install some Python dependencies. If using ``pip`` to install these dependencies, you may want to create a virtual environment.
44+
45+
.. code-block:: bash
46+
47+
python3 -m venv .venv
48+
source .venv/bin/activate
49+
50+
You can then install requirements using ``pip``:
51+
52+
.. code-block:: bash
53+
54+
pip3 install --upgrade --requirement requirements.txt
55+
56+
You can run the ``htmlproofer`` script with this command:
4457

4558
.. code-block:: bash
4659

doc/how_to_guides/how_to_setup_docker_containers_in_ubuntu.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ Further Reading
5050
refer to `this blog post <https://picknik.ai/ros/robotics/docker/2021/07/20/Vatan-Aksoy-Tezer-Docker.html>`_
5151
from PickNik's Vatan Aksoy Tezer and Brennard Pierce.
5252

53-
- You can find a list of tagged tutorial images `here <https://github.com/moveit/moveit2_tutorials/pkgs/container/moveit2_tutorials>`__. There are tagged images for both ``rolling`` and ``humble`` which are built on top of the ``rolling-source`` and ``humble-source`` MoveIt 2 Docker images `here <https://hub.docker.com/r/moveit/moveit2/tags>`__.
53+
- There are tagged images for both ``rolling`` and ``humble`` which are built on top of the ``rolling-source`` and ``humble-source`` MoveIt 2 Docker images `here <https://hub.docker.com/r/moveit/moveit2/tags>`__.
5454

5555
- You can find more tagged images for MoveIt 2 Docker containers `here <https://hub.docker.com/r/moveit/moveit2/tags>`__.
5656
The tagged images coincide with ROS2 version releases. The ``release`` version of the container provides an environment in which MoveIt 2 is installed via the binaries.

doc/how_to_guides/pilz_industrial_motion_planner/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,15 @@ add_executable(pilz_mtc src/pilz_mtc.cpp)
66
target_include_directories(pilz_mtc PUBLIC include)
77
ament_target_dependencies(pilz_mtc ${THIS_PACKAGE_INCLUDE_DEPENDS})
88

9+
add_executable(pilz_sequence src/pilz_sequence.cpp)
10+
target_include_directories(pilz_sequence PUBLIC include)
11+
ament_target_dependencies(pilz_sequence ${THIS_PACKAGE_INCLUDE_DEPENDS})
12+
913
install(
1014
TARGETS
1115
pilz_move_group
1216
pilz_mtc
17+
pilz_sequence
1318
DESTINATION
1419
lib/${PROJECT_NAME}
1520
)
Lines changed: 111 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,111 @@
1+
import os
2+
from launch import LaunchDescription
3+
from launch_ros.actions import Node
4+
from launch.actions import ExecuteProcess
5+
from ament_index_python.packages import get_package_share_directory
6+
from moveit_configs_utils import MoveItConfigsBuilder
7+
8+
9+
def generate_launch_description():
10+
moveit_config = (
11+
MoveItConfigsBuilder("moveit_resources_panda")
12+
.robot_description(file_path="config/panda.urdf.xacro")
13+
.trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
14+
.planning_scene_monitor(
15+
publish_robot_description=True, publish_robot_description_semantic=True
16+
)
17+
.planning_pipelines(pipelines=["pilz_industrial_motion_planner"])
18+
.to_moveit_configs()
19+
)
20+
21+
# Starts Pilz Industrial Motion Planner MoveGroupSequenceAction and MoveGroupSequenceService servers
22+
move_group_capabilities = {
23+
"capabilities": "pilz_industrial_motion_planner/MoveGroupSequenceAction pilz_industrial_motion_planner/MoveGroupSequenceService"
24+
}
25+
26+
# Start the actual move_group node/action server
27+
run_move_group_node = Node(
28+
package="moveit_ros_move_group",
29+
executable="move_group",
30+
output="screen",
31+
parameters=[
32+
moveit_config.to_dict(),
33+
move_group_capabilities,
34+
],
35+
)
36+
37+
# RViz
38+
rviz_config_file = (
39+
get_package_share_directory("moveit2_tutorials") + "/launch/move_group.rviz"
40+
)
41+
rviz_node = Node(
42+
package="rviz2",
43+
executable="rviz2",
44+
name="rviz2",
45+
output="log",
46+
arguments=["-d", rviz_config_file],
47+
parameters=[
48+
moveit_config.robot_description,
49+
moveit_config.robot_description_semantic,
50+
moveit_config.robot_description_kinematics,
51+
moveit_config.planning_pipelines,
52+
moveit_config.joint_limits,
53+
],
54+
)
55+
56+
# Static TF
57+
static_tf = Node(
58+
package="tf2_ros",
59+
executable="static_transform_publisher",
60+
name="static_transform_publisher",
61+
output="log",
62+
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "panda_link0"],
63+
)
64+
65+
# Publish TF
66+
robot_state_publisher = Node(
67+
package="robot_state_publisher",
68+
executable="robot_state_publisher",
69+
name="robot_state_publisher",
70+
output="both",
71+
parameters=[moveit_config.robot_description],
72+
)
73+
74+
# ros2_control using FakeSystem as hardware
75+
ros2_controllers_path = os.path.join(
76+
get_package_share_directory("moveit_resources_panda_moveit_config"),
77+
"config",
78+
"ros2_controllers.yaml",
79+
)
80+
ros2_control_node = Node(
81+
package="controller_manager",
82+
executable="ros2_control_node",
83+
parameters=[moveit_config.robot_description, ros2_controllers_path],
84+
output="both",
85+
)
86+
87+
# Load controllers
88+
load_controllers = []
89+
for controller in [
90+
"panda_arm_controller",
91+
"panda_hand_controller",
92+
"joint_state_broadcaster",
93+
]:
94+
load_controllers += [
95+
ExecuteProcess(
96+
cmd=["ros2 run controller_manager spawner {}".format(controller)],
97+
shell=True,
98+
output="screen",
99+
)
100+
]
101+
102+
return LaunchDescription(
103+
[
104+
rviz_node,
105+
static_tf,
106+
robot_state_publisher,
107+
run_move_group_node,
108+
ros2_control_node,
109+
]
110+
+ load_controllers
111+
)

0 commit comments

Comments
 (0)