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

Adding moveit config pkg foxy #25

Open
wants to merge 12 commits into
base: foxy
Choose a base branch
from
39 changes: 39 additions & 0 deletions kuka_common_moveit_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
cmake_minimum_required(VERSION 3.5)
project(kuka_common_moveit_config)

# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
install(DIRECTORY
config
launch
DESTINATION share/${PROJECT_NAME}/
)
ament_package()
18 changes: 18 additions & 0 deletions kuka_common_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
smoothness_cost_weight: 0.1
obstacle_cost_weight: 1.0
learning_rate: 0.01
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
ridge_factor: 0.01
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
joint_update_limit: 0.1
collision_clearence: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
13 changes: 13 additions & 0 deletions kuka_common_moveit_config/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
controller_list:
- name: fake_manipulator_controller
type: $(arg execution_type)
joints:
- joint_a1
- joint_a2
- joint_a3
- joint_a4
- joint_a5
- joint_a6
initial: # Define initial robot poses.
- group: manipulator
pose: home
46 changes: 46 additions & 0 deletions kuka_common_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
joint_a1:
has_velocity_limits: true
# max_velocity: 9.250245035569947
max_velocity: 0.9250245035569947
has_acceleration_limits: false
max_acceleration: 0
joint_a2:
has_velocity_limits: true
# max_velocity: 9.232791743050003
max_velocity: 0.9232791743050003
has_acceleration_limits: false
max_acceleration: 0
joint_a3:
has_velocity_limits: true
# max_velocity: 9.389871375729493
max_velocity: 0.9389871375729493
has_acceleration_limits: false
max_acceleration: 0
joint_a4:
has_velocity_limits: true
# max_velocity: 10.47197551196598
max_velocity: 1.047197551196598
has_acceleration_limits: false
max_acceleration: 0
joint_a5:
has_velocity_limits: true
# max_velocity: 10.47197551196598
max_velocity: 1.047197551196598
has_acceleration_limits: false
max_acceleration: 0
joint_a6:
has_velocity_limits: true
# max_velocity: 13.96263401595464
max_velocity: 1.396263401595464
has_acceleration_limits: false
max_acceleration: 0
4 changes: 4 additions & 0 deletions kuka_common_moveit_config/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
40 changes: 40 additions & 0 deletions kuka_common_moveit_config/config/kr10r1100sixx.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--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="kuka_kr10">
<!--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="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>

<group_state name="home" group="manipulator">
<joint name="joint_a1" value="0"/>
<joint name="joint_a2" value="-1.57"/>
<joint name="joint_a3" value="1.57"/>
<joint name="joint_a4" value="0"/>
<joint name="joint_a5" value="1.57"/>
<joint name="joint_a6" value="0"/>
</group_state>
<!--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="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_4" reason="Never"/>
<disable_collisions link1="link_1" link2="link_6" reason="Never"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_2" link2="link_6" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
39 changes: 39 additions & 0 deletions kuka_common_moveit_config/config/kr10r900_2.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--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="kuka_kr10">
<!--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="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>

<group_state name="home" group="manipulator">
<joint name="joint_a1" value="0"/>
<joint name="joint_a2" value="-1.57"/>
<joint name="joint_a3" value="1.57"/>
<joint name="joint_a4" value="0"/>
<joint name="joint_a5" value="1.57"/>
<joint name="joint_a6" value="0"/>
</group_state>
<!--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="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_4" reason="Never"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_2" link2="link_6" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
35 changes: 35 additions & 0 deletions kuka_common_moveit_config/config/kr120r2500pro.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--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="kuka_kr120">
<!--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="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>

<group_state name="home" group="manipulator">
<joint name="joint_a1" value="0"/>
<joint name="joint_a2" value="-1.57"/>
<joint name="joint_a3" value="1.57"/>
<joint name="joint_a4" value="0"/>
<joint name="joint_a5" value="1.57"/>
<joint name="joint_a6" value="0"/>
</group_state>
<!--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="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_4" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
38 changes: 38 additions & 0 deletions kuka_common_moveit_config/config/kr150_2.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--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="kuka_kr150">
<!--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="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>

<group_state name="home" group="manipulator">
<joint name="joint_a1" value="0"/>
<joint name="joint_a2" value="-1.57"/>
<joint name="joint_a3" value="1.57"/>
<joint name="joint_a4" value="0"/>
<joint name="joint_a5" value="1.57"/>
<joint name="joint_a6" value="0"/>
</group_state>
<!--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="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_2" reason="Never"/>
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
38 changes: 38 additions & 0 deletions kuka_common_moveit_config/config/kr150r3100_2.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--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="kuka_kr150">
<!--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="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>

<group_state name="home" group="manipulator">
<joint name="joint_a1" value="0"/>
<joint name="joint_a2" value="-1.57"/>
<joint name="joint_a3" value="1.57"/>
<joint name="joint_a4" value="0"/>
<joint name="joint_a5" value="1.57"/>
<joint name="joint_a6" value="0"/>
</group_state>
<!--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="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_2" reason="Never"/>
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
Loading