Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ros2-ified #136

Draft
wants to merge 7 commits into
base: rolling-devel
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 22 additions & 8 deletions .setup_assistant
Original file line number Diff line number Diff line change
@@ -1,11 +1,25 @@
moveit_setup_assistant_config:
URDF:
package: franka_description
relative_path: robots/panda/panda.urdf.xacro
xacro_args: hand:=true
Comment on lines -3 to -5
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

panda_moveit_config should rely on franka_description, not on moveit_resources_panda_description.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Makes sense especially having seen your comment moveit/moveit2_tutorials#61 (comment), which tells me the switch from panda_moveit_config to moveit_resources_panda_moveit_config in moveit2_tutorial might be unlikely a widely agreed move. Then, the entire PR will have to be re-done because the PR at the time of writing is made referencing to the model files in moveit_resources_panda_description package. Made the PR back to draft state.

SRDF:
relative_path: config/panda.srdf.xacro
CONFIG:
urdf:
package: moveit_resources_panda_description
relative_path: urdf/panda.urdf
srdf:
relative_path: config/panda.srdf
package_settings:
author_name: MoveIt maintainer team
author_email: moveit_releasers@googlegroups.com
generated_timestamp: 1636310680
generated_timestamp: 1686150423
control_xacro:
command:
- position
state:
- position
- velocity
modified_urdf:
xacros:
- control_xacro
control_xacro:
command:
- position
state:
- position
- velocity
12 changes: 6 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
cmake_minimum_required(VERSION 3.1.3)
cmake_minimum_required(VERSION 3.22)
project(panda_moveit_config)

find_package(catkin REQUIRED)
find_package(ament_cmake REQUIRED)

catkin_package()
install(DIRECTORY config ros1 DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
ament_package()
11 changes: 11 additions & 0 deletions config/initial_positions.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
# Default initial positions for panda's ros2_control fake system

initial_positions:
panda_finger_joint1: 0
panda_joint1: 0
panda_joint2: 0
panda_joint3: 0
panda_joint4: 0
panda_joint5: 0
panda_joint6: 0
panda_joint7: 0
51 changes: 51 additions & 0 deletions config/moveit.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
Panels:
- Class: rviz_common/Displays
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- Class: rviz_common/Help
Name: Help
- Class: rviz_common/Views
Name: Views
Visualization Manager:
Displays:
- Class: rviz_default_plugins/Grid
Name: Grid
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
Name: MotionPlanning
Planned Path:
Loop Animation: true
State Display Time: 0.05 s
Trajectory Topic: display_planned_path
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Robot:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: panda_link0
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.0
Focal Point:
X: -0.1
Y: 0.25
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: panda_link0
Yaw: -0.623
Window Geometry:
Height: 975
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1200
27 changes: 27 additions & 0 deletions config/moveit_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# MoveIt uses this configuration for controller management

moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager

moveit_simple_controller_manager:
controller_names:
- panda_arm_controller
- hand_controller

panda_arm_controller:
type: FollowJointTrajectory
action_ns: follow_joint_trajectory
default: true
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
hand_controller:
type: GripperCommand
joints:
- panda_finger_joint1
action_ns: gripper_cmd
default: true
70 changes: 70 additions & 0 deletions config/panda.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="panda_ros2_control" params="name initial_positions_file">
<xacro:property name="initial_positions" value="${load_yaml(initial_positions_file)['initial_positions']}"/>

<ros2_control name="${name}" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<joint name="panda_joint1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint2">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint2']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint3">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint3']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint4">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint4']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint5">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint5']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint6">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint6']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_joint7">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_joint7']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="panda_finger_joint1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['panda_finger_joint1']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>

</ros2_control>
</xacro:macro>
</robot>
84 changes: 84 additions & 0 deletions config/panda.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
<?xml version="1.0" encoding="UTF-8"?>
130s marked this conversation as resolved.
Show resolved Hide resolved
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="panda">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--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-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="panda_arm">
<joint name="virtual_joint"/>
<joint name="panda_joint1"/>
<joint name="panda_joint2"/>
<joint name="panda_joint3"/>
<joint name="panda_joint4"/>
<joint name="panda_joint5"/>
<joint name="panda_joint6"/>
<joint name="panda_joint7"/>
<joint name="panda_joint8"/>
</group>
<group name="hand">
<link name="panda_hand"/>
<link name="panda_leftfinger"/>
<link name="panda_rightfinger"/>
</group>
<!--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'-->
<group_state name="ready" group="panda_arm">
<joint name="panda_joint1" value="0"/>
<joint name="panda_joint2" value="-0.785"/>
<joint name="panda_joint3" value="0"/>
<joint name="panda_joint4" value="-2.356"/>
<joint name="panda_joint5" value="0"/>
<joint name="panda_joint6" value="1.571"/>
<joint name="panda_joint7" value="0.785"/>
</group_state>
<group_state name="open" group="hand">
<joint name="panda_finger_joint1" value="0.035"/>
</group_state>
<group_state name="close" group="hand">
<joint name="panda_finger_joint1" value="0"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="hand" parent_link="panda_link8" group="hand"/>
<!--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)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0"/>
<!--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. -->
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent"/>
<disable_collisions link1="panda_hand" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default"/>
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent"/>
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default"/>
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent"/>
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/>
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/>
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/>
<disable_collisions link1="panda_link3" link2="panda_link5" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent"/>
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent"/>
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default"/>
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent"/>
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never"/>
</robot>
14 changes: 14 additions & 0 deletions config/panda.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />

<!-- Import panda urdf file -->
<xacro:include filename="$(find moveit_resources_panda_description)/urdf/panda.urdf" />
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

panda_moveit_config should rely on franka_description, not on moveit_resources_panda_description.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pending decision in moveit/moveit2_tutorials#704


<!-- Import control_xacro -->
<xacro:include filename="panda.ros2_control.xacro" />


<xacro:panda_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/>

</robot>
6 changes: 6 additions & 0 deletions config/pilz_cartesian_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Limits for the Pilz planner
cartesian_limits:
max_trans_vel: 1.0
max_trans_acc: 2.25
max_trans_dec: -5.0
max_rot_vel: 1.57
34 changes: 34 additions & 0 deletions config/ros2_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# This config file is used by ros2_control
controller_manager:
ros__parameters:
update_rate: 100 # Hz

panda_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController


hand_controller:
type: position_controllers/GripperActionController


joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

panda_arm_controller:
ros__parameters:
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
command_interfaces:
- position
state_interfaces:
- position
- velocity
hand_controller:
ros__parameters:
joint: panda_finger_joint1
7 changes: 7 additions & 0 deletions launch/demo.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_demo_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
return generate_demo_launch(moveit_config)
7 changes: 7 additions & 0 deletions launch/move_group.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
return generate_move_group_launch(moveit_config)
7 changes: 7 additions & 0 deletions launch/moveit_rviz.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_moveit_rviz_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config)
7 changes: 7 additions & 0 deletions launch/rsp.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_rsp_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder("panda", package_name="panda_moveit_config").to_moveit_configs()
return generate_rsp_launch(moveit_config)
Loading