Skip to content

Commit 03fd8ec

Browse files
committed
Add hangar_sim
Signed-off-by: Paul Gesel <paul.gesel@picknik.ai>
1 parent a21d5a5 commit 03fd8ec

File tree

1,105 files changed

+17769
-394159
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

1,105 files changed

+17769
-394159
lines changed

.gitattributes

+10
Original file line numberDiff line numberDiff line change
@@ -1 +1,11 @@
1+
# Add Git LFS support for common 3D file formats
12
*.onnx filter=lfs diff=lfs merge=lfs -text
3+
*.stl filter=lfs diff=lfs merge=lfs -text
4+
*.obj filter=lfs diff=lfs merge=lfs -text
5+
*.fbx filter=lfs diff=lfs merge=lfs -text
6+
*.dae filter=lfs diff=lfs merge=lfs -text
7+
*.gltf filter=lfs diff=lfs merge=lfs -text
8+
*.glb filter=lfs diff=lfs merge=lfs -text
9+
*.ply filter=lfs diff=lfs merge=lfs -text
10+
*.3ds filter=lfs diff=lfs merge=lfs -text
11+
*.blend filter=lfs diff=lfs merge=lfs -text

.gitmodules

+3
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,6 @@
44
[submodule "src/external_dependencies/Universal_Robots_ROS2_Description"]
55
path = src/external_dependencies/ur_description
66
url = https://github.com/PickNikRobotics/Universal_Robots_ROS2_Description.git
7+
[submodule "src/external_dependencies/clearpath_mecanum_drive_controller"]
8+
path = src/external_dependencies/clearpath_mecanum_drive_controller
9+
url = https://github.com/PickNikRobotics/clearpath_mecanum_drive_controller.git

README.md

+1-1

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/left_finger.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/left_finger_tip.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/left_inner_knuckle.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/left_knuckle.dae

+3-98
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/right_finger.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/right_finger_tip.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/right_inner_knuckle.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/right_knuckle.dae

+3-98
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/robotiq_base.dae

+3-133
Large diffs are not rendered by default.

src/external_dependencies/ros2_robotiq_gripper/robotiq_description/meshes/visual/2f_85/ur_to_robotiq_adapter.dae

+3-136
Large diffs are not rendered by default.

src/hangar_sim/CMakeLists.txt

+38
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
cmake_minimum_required(VERSION 3.22)
2+
project(hangar_sim)
3+
4+
find_package(ament_cmake REQUIRED)
5+
find_package(picknik_accessories REQUIRED)
6+
find_package(pluginlib REQUIRED)
7+
find_package(moveit_studio_plugins REQUIRED)
8+
9+
install(
10+
DIRECTORY
11+
config
12+
description
13+
launch
14+
maps
15+
objectives
16+
params
17+
waypoints
18+
DESTINATION
19+
share/${PROJECT_NAME}
20+
)
21+
22+
pluginlib_export_plugin_description_file(
23+
moveit_ros_control_interface moveit_mecanum_drive_controller_plugins.xml)
24+
25+
install(PROGRAMS
26+
script/odometry_joint_state_publisher.py
27+
DESTINATION lib/${PROJECT_NAME}
28+
)
29+
30+
install(IMPORTED_RUNTIME_ARTIFACTS moveit_studio_plugins::dummy_controller_handle_plugin LIBRARY DESTINATION
31+
lib)
32+
33+
if(BUILD_TESTING)
34+
find_package(ament_lint_auto REQUIRED)
35+
ament_lint_auto_find_test_dependencies()
36+
endif()
37+
38+
ament_package()

src/hangar_sim/README.md

+5
+40-21
Original file line numberDiff line numberDiff line change
@@ -10,26 +10,47 @@ hardware:
1010
# [Required]
1111
robot_description:
1212
urdf:
13-
package: "picknik_ur_mobile_config"
14-
path: "description/picknik_ur.xacro"
13+
package: "hangar_sim"
14+
path: "description/ur5e_ridgeback.xacro"
1515
srdf:
16-
package: "picknik_ur_mobile_config"
16+
package: "hangar_sim"
1717
path: "config/moveit/picknik_ur.srdf"
1818
urdf_params:
1919
- joint_limits_parameters_file:
20-
package: "picknik_ur_mobile_config"
20+
package: "hangar_sim"
2121
path: "config/moveit/joint_limits.yaml"
22+
- mujoco_model: "description/hangar_scene.xml"
23+
24+
# Specify any additional launch files for running the robot in simulation mode.
25+
# Used when hardware.simulated is True.
26+
# [Optional, defaults to a blank launch file if not specified]
27+
simulated_robot_driver_persist_launch_file:
28+
package: "hangar_sim"
29+
path: "launch/sim/robot_drivers_to_persist_sim.launch.py"
2230

2331
moveit_params:
2432
servo:
25-
package: "picknik_ur_mobile_config"
33+
package: "hangar_sim"
2634
path: "config/moveit/ur_servo.yaml"
2735
joint_limits:
28-
package: "picknik_ur_mobile_config"
36+
package: "hangar_sim"
2937
path: "config/moveit/joint_limits.yaml"
3038
servo_joint_limits:
31-
package: "picknik_ur_mobile_config"
39+
package: "hangar_sim"
3240
path: "config/moveit/hard_joint_limits.yaml"
41+
kinematics:
42+
package: "hangar_sim"
43+
path: "config/moveit/trac_ik_kinematics_distance.yaml"
44+
servo_kinematics:
45+
package: "hangar_sim"
46+
path: "config/moveit/trac_ik_kinematics_speed.yaml"
47+
sensors_3d:
48+
package: "hangar_sim"
49+
path: "config/moveit/sensors_3d.yaml"
50+
ompl_planning:
51+
package: "hangar_sim"
52+
path: "config/moveit/ompl_planning.yaml"
53+
3354

3455
# Configuration for loading behaviors and objectives.
3556
# [Required]
@@ -42,42 +63,40 @@ objectives:
4263
core:
4364
- "moveit_studio::behaviors::CoreBehaviorsLoader"
4465
- "moveit_studio::behaviors::MTCCoreBehaviorsLoader"
66+
- "moveit_studio::behaviors::NavBehaviorsLoader"
4567
- "moveit_studio::behaviors::ServoBehaviorsLoader"
4668
- "moveit_studio::behaviors::VisionBehaviorsLoader"
4769
# Specify source folder for objectives
4870
# [Required]
4971
objective_library_paths:
50-
sim_objectives:
51-
package_name: "picknik_ur_mobile_config"
72+
hangar_sim_objectives:
73+
package_name: "hangar_sim"
5274
relative_path: "objectives"
75+
5376
# Specify the location of the saved waypoints file.
5477
# [Required]
5578
waypoints_file:
56-
package_name: "picknik_ur_mobile_config"
79+
package_name: "hangar_sim"
5780
relative_path: "waypoints/ur_waypoints.yaml"
5881

59-
6082
# Configuration for launching ros2_control processes.
6183
# [Required, if using ros2_control]
6284
ros2_control:
6385
config:
64-
package: "picknik_ur_mobile_config"
86+
package: "hangar_sim"
6587
path: "config/control/picknik_ur.ros2_control.yaml"
88+
6689
# MoveIt Pro will load and activate these controllers at start up to ensure they are available.
6790
# If not specified, it is up to the user to ensure the appropriate controllers are active and available
6891
# for running the application.
6992
# [Optional, default=[]]
7093
controllers_active_at_startup:
7194
- "force_torque_sensor_broadcaster"
72-
- "robotiq_gripper_controller"
7395
- "joint_state_broadcaster"
74-
- "servo_controller"
96+
- "joint_trajectory_controller"
97+
- "platform_velocity_controller"
98+
- "vacuum_gripper"
7599
# Load but do not start these controllers so they can be activated later if needed.
76100
controllers_inactive_at_startup:
77-
- "joint_trajectory_controller"
78-
# Any controllers here will not be spawned by MoveIt Pro.
79-
# [Optional, default=[]]
80-
controllers_not_managed: []
81-
# Optionally configure remapping rules to let multiple controllers receive commands on the same topic.
82-
# [Optional, default=[]]
83-
controller_shared_topics: []
101+
- "servo_controller"
102+
- "platform_velocity_controller_nav2"

0 commit comments

Comments
 (0)