Skip to content

Commit 4441e44

Browse files
committed
ros2-fy: Merge with the files that are generated from MSA 2.5.4
1 parent 73c9a66 commit 4441e44

19 files changed

+402
-28
lines changed

.setup_assistant

+22-8
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,25 @@
11
moveit_setup_assistant_config:
2-
URDF:
3-
package: franka_description
4-
relative_path: robots/panda_arm.urdf.xacro
5-
xacro_args: hand:=true
6-
SRDF:
7-
relative_path: config/panda.srdf.xacro
8-
CONFIG:
2+
urdf:
3+
package: moveit_resources_panda_description
4+
relative_path: urdf/panda.urdf
5+
srdf:
6+
relative_path: config/panda.srdf
7+
package_settings:
98
author_name: MoveIt maintainer team
109
author_email: [email protected]
11-
generated_timestamp: 1636310680
10+
generated_timestamp: 1686150423
11+
control_xacro:
12+
command:
13+
- position
14+
state:
15+
- position
16+
- velocity
17+
modified_urdf:
18+
xacros:
19+
- control_xacro
20+
control_xacro:
21+
command:
22+
- position
23+
state:
24+
- position
25+
- velocity

CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
1-
cmake_minimum_required(VERSION 3.8)
1+
cmake_minimum_required(VERSION 3.22)
22
project(panda_moveit_config)
33

44
find_package(ament_cmake REQUIRED)
5-
find_package(ament_cmake_python REQUIRED)
65

76
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
87
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}
98
PATTERN "setup_assistant.launch" EXCLUDE)
9+
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})
1010

1111
ament_package()

config/initial_positions.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# Default initial positions for panda's ros2_control fake system
2+
3+
initial_positions:
4+
panda_finger_joint1: 0
5+
panda_joint1: 0
6+
panda_joint2: 0
7+
panda_joint3: 0
8+
panda_joint4: 0
9+
panda_joint5: 0
10+
panda_joint6: 0
11+
panda_joint7: 0

config/moveit.rviz

+51
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
Panels:
2+
- Class: rviz_common/Displays
3+
Name: Displays
4+
Property Tree Widget:
5+
Expanded:
6+
- /MotionPlanning1
7+
- Class: rviz_common/Help
8+
Name: Help
9+
- Class: rviz_common/Views
10+
Name: Views
11+
Visualization Manager:
12+
Displays:
13+
- Class: rviz_default_plugins/Grid
14+
Name: Grid
15+
Value: true
16+
- Class: moveit_rviz_plugin/MotionPlanning
17+
Name: MotionPlanning
18+
Planned Path:
19+
Loop Animation: true
20+
State Display Time: 0.05 s
21+
Trajectory Topic: display_planned_path
22+
Planning Scene Topic: monitored_planning_scene
23+
Robot Description: robot_description
24+
Scene Geometry:
25+
Scene Alpha: 1
26+
Scene Robot:
27+
Robot Alpha: 0.5
28+
Value: true
29+
Global Options:
30+
Fixed Frame: panda_link0
31+
Tools:
32+
- Class: rviz_default_plugins/Interact
33+
- Class: rviz_default_plugins/MoveCamera
34+
- Class: rviz_default_plugins/Select
35+
Value: true
36+
Views:
37+
Current:
38+
Class: rviz_default_plugins/Orbit
39+
Distance: 2.0
40+
Focal Point:
41+
X: -0.1
42+
Y: 0.25
43+
Z: 0.30
44+
Name: Current View
45+
Pitch: 0.5
46+
Target Frame: panda_link0
47+
Yaw: -0.623
48+
Window Geometry:
49+
Height: 975
50+
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
51+
Width: 1200

config/moveit_controllers.yaml

+27
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
# MoveIt uses this configuration for controller management
2+
3+
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
4+
5+
moveit_simple_controller_manager:
6+
controller_names:
7+
- panda_arm_controller
8+
- hand_controller
9+
10+
panda_arm_controller:
11+
type: FollowJointTrajectory
12+
action_ns: follow_joint_trajectory
13+
default: true
14+
joints:
15+
- panda_joint1
16+
- panda_joint2
17+
- panda_joint3
18+
- panda_joint4
19+
- panda_joint5
20+
- panda_joint6
21+
- panda_joint7
22+
hand_controller:
23+
type: GripperCommand
24+
joints:
25+
- panda_finger_joint1
26+
action_ns: gripper_cmd
27+
default: true

config/panda.ros2_control.xacro

+70
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
<xacro:macro name="panda_ros2_control" params="name initial_positions_file">
4+
<xacro:property name="initial_positions" value="${load_yaml(initial_positions_file)['initial_positions']}"/>
5+
6+
<ros2_control name="${name}" type="system">
7+
<hardware>
8+
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
9+
<plugin>mock_components/GenericSystem</plugin>
10+
</hardware>
11+
<joint name="panda_joint1">
12+
<command_interface name="position"/>
13+
<state_interface name="position">
14+
<param name="initial_value">${initial_positions['panda_joint1']}</param>
15+
</state_interface>
16+
<state_interface name="velocity"/>
17+
</joint>
18+
<joint name="panda_joint2">
19+
<command_interface name="position"/>
20+
<state_interface name="position">
21+
<param name="initial_value">${initial_positions['panda_joint2']}</param>
22+
</state_interface>
23+
<state_interface name="velocity"/>
24+
</joint>
25+
<joint name="panda_joint3">
26+
<command_interface name="position"/>
27+
<state_interface name="position">
28+
<param name="initial_value">${initial_positions['panda_joint3']}</param>
29+
</state_interface>
30+
<state_interface name="velocity"/>
31+
</joint>
32+
<joint name="panda_joint4">
33+
<command_interface name="position"/>
34+
<state_interface name="position">
35+
<param name="initial_value">${initial_positions['panda_joint4']}</param>
36+
</state_interface>
37+
<state_interface name="velocity"/>
38+
</joint>
39+
<joint name="panda_joint5">
40+
<command_interface name="position"/>
41+
<state_interface name="position">
42+
<param name="initial_value">${initial_positions['panda_joint5']}</param>
43+
</state_interface>
44+
<state_interface name="velocity"/>
45+
</joint>
46+
<joint name="panda_joint6">
47+
<command_interface name="position"/>
48+
<state_interface name="position">
49+
<param name="initial_value">${initial_positions['panda_joint6']}</param>
50+
</state_interface>
51+
<state_interface name="velocity"/>
52+
</joint>
53+
<joint name="panda_joint7">
54+
<command_interface name="position"/>
55+
<state_interface name="position">
56+
<param name="initial_value">${initial_positions['panda_joint7']}</param>
57+
</state_interface>
58+
<state_interface name="velocity"/>
59+
</joint>
60+
<joint name="panda_finger_joint1">
61+
<command_interface name="position"/>
62+
<state_interface name="position">
63+
<param name="initial_value">${initial_positions['panda_finger_joint1']}</param>
64+
</state_interface>
65+
<state_interface name="velocity"/>
66+
</joint>
67+
68+
</ros2_control>
69+
</xacro:macro>
70+
</robot>

config/panda.srdf

+84
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,84 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!--This does not replace URDF, and is not an extension of URDF.
3+
This is a format for representing semantic information about the robot structure.
4+
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
5+
-->
6+
<robot name="panda">
7+
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
8+
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
9+
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
10+
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
11+
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
12+
<group name="panda_arm">
13+
<joint name="virtual_joint"/>
14+
<joint name="panda_joint1"/>
15+
<joint name="panda_joint2"/>
16+
<joint name="panda_joint3"/>
17+
<joint name="panda_joint4"/>
18+
<joint name="panda_joint5"/>
19+
<joint name="panda_joint6"/>
20+
<joint name="panda_joint7"/>
21+
<joint name="panda_joint8"/>
22+
</group>
23+
<group name="hand">
24+
<link name="panda_hand"/>
25+
<link name="panda_leftfinger"/>
26+
<link name="panda_rightfinger"/>
27+
</group>
28+
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
29+
<group_state name="ready" group="panda_arm">
30+
<joint name="panda_joint1" value="0"/>
31+
<joint name="panda_joint2" value="-0.785"/>
32+
<joint name="panda_joint3" value="0"/>
33+
<joint name="panda_joint4" value="-2.356"/>
34+
<joint name="panda_joint5" value="0"/>
35+
<joint name="panda_joint6" value="1.571"/>
36+
<joint name="panda_joint7" value="0.785"/>
37+
</group_state>
38+
<group_state name="open" group="hand">
39+
<joint name="panda_finger_joint1" value="0.035"/>
40+
</group_state>
41+
<group_state name="close" group="hand">
42+
<joint name="panda_finger_joint1" value="0"/>
43+
</group_state>
44+
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
45+
<end_effector name="hand" parent_link="panda_link8" group="hand"/>
46+
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
47+
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0"/>
48+
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
49+
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent"/>
50+
<disable_collisions link1="panda_hand" link2="panda_link3" reason="Never"/>
51+
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never"/>
52+
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default"/>
53+
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never"/>
54+
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent"/>
55+
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent"/>
56+
<disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never"/>
57+
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never"/>
58+
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never"/>
59+
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never"/>
60+
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default"/>
61+
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent"/>
62+
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never"/>
63+
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never"/>
64+
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/>
65+
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/>
66+
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Never"/>
67+
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/>
68+
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/>
69+
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/>
70+
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/>
71+
<disable_collisions link1="panda_link3" link2="panda_link5" reason="Never"/>
72+
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never"/>
73+
<disable_collisions link1="panda_link3" link2="panda_link7" reason="Never"/>
74+
<disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never"/>
75+
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent"/>
76+
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never"/>
77+
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never"/>
78+
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never"/>
79+
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent"/>
80+
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default"/>
81+
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent"/>
82+
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never"/>
83+
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never"/>
84+
</robot>

config/panda.urdf.xacro

+14
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
3+
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
4+
5+
<!-- Import panda urdf file -->
6+
<xacro:include filename="$(find moveit_resources_panda_description)/urdf/panda.urdf" />
7+
8+
<!-- Import control_xacro -->
9+
<xacro:include filename="panda.ros2_control.xacro" />
10+
11+
12+
<xacro:panda_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/>
13+
14+
</robot>

config/pilz_cartesian_limits.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
# Limits for the Pilz planner
2+
cartesian_limits:
3+
max_trans_vel: 1.0
4+
max_trans_acc: 2.25
5+
max_trans_dec: -5.0
6+
max_rot_vel: 1.57

config/ros2_controllers.yaml

+34
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
# This config file is used by ros2_control
2+
controller_manager:
3+
ros__parameters:
4+
update_rate: 100 # Hz
5+
6+
panda_arm_controller:
7+
type: joint_trajectory_controller/JointTrajectoryController
8+
9+
10+
hand_controller:
11+
type: position_controllers/GripperActionController
12+
13+
14+
joint_state_broadcaster:
15+
type: joint_state_broadcaster/JointStateBroadcaster
16+
17+
panda_arm_controller:
18+
ros__parameters:
19+
joints:
20+
- panda_joint1
21+
- panda_joint2
22+
- panda_joint3
23+
- panda_joint4
24+
- panda_joint5
25+
- panda_joint6
26+
- panda_joint7
27+
command_interfaces:
28+
- position
29+
state_interfaces:
30+
- position
31+
- velocity
32+
hand_controller:
33+
ros__parameters:
34+
joint: panda_finger_joint1

launch/demo.launch.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
from moveit_configs_utils import MoveItConfigsBuilder
2+
from moveit_configs_utils.launches import generate_demo_launch
3+
4+
5+
def generate_launch_description():
6+
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
7+
return generate_demo_launch(moveit_config)

launch/move_group.launch.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
from moveit_configs_utils import MoveItConfigsBuilder
2+
from moveit_configs_utils.launches import generate_move_group_launch
3+
4+
5+
def generate_launch_description():
6+
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
7+
return generate_move_group_launch(moveit_config)

launch/moveit_rviz.launch.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
from moveit_configs_utils import MoveItConfigsBuilder
2+
from moveit_configs_utils.launches import generate_moveit_rviz_launch
3+
4+
5+
def generate_launch_description():
6+
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
7+
return generate_moveit_rviz_launch(moveit_config)

launch/rsp.launch.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
from moveit_configs_utils import MoveItConfigsBuilder
2+
from moveit_configs_utils.launches import generate_rsp_launch
3+
4+
5+
def generate_launch_description():
6+
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
7+
return generate_rsp_launch(moveit_config)

launch/setup_assistant.launch.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
from moveit_configs_utils import MoveItConfigsBuilder
2+
from moveit_configs_utils.launches import generate_setup_assistant_launch
3+
4+
5+
def generate_launch_description():
6+
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
7+
return generate_setup_assistant_launch(moveit_config)

0 commit comments

Comments
 (0)