From 2650b088f6dc48e605517308459a8db5fa826bc8 Mon Sep 17 00:00:00 2001 From: Bastian Hofmann Date: Tue, 15 Mar 2022 05:53:38 +0100 Subject: [PATCH] basic import of generated iisy_config --- src/gaz_simulation/.package.xml.kate-swp | Bin 334 -> 0 bytes .../launch/.moveit_launch.py.kate-swp | Bin 0 -> 169 bytes src/gaz_simulation/launch/moveit_launch.py | 114 +++++++++++++ src/gaz_simulation/launch/test_launch.py | 1 + src/gaz_simulation/package.xml | 2 +- src/gaz_simulation/urdf/iisy.urdf | 9 +- src/iisy_config/.setup_assistant | 11 ++ src/iisy_config/CMakeLists.txt | 28 ++++ src/iisy_config/config/cartesian_limits.yaml | 5 + src/iisy_config/config/chomp_planning.yaml | 18 ++ src/iisy_config/config/fake_controllers.yaml | 13 ++ .../config/gazebo_controllers.yaml | 4 + src/iisy_config/config/iisy.srdf | 39 +++++ src/iisy_config/config/joint_limits.yaml | 40 +++++ src/iisy_config/config/kinematics.yaml | 4 + src/iisy_config/config/ompl_planning.yaml | 157 ++++++++++++++++++ src/iisy_config/config/ros_controllers.yaml | 40 +++++ src/iisy_config/config/sensors_3d.yaml | 2 + .../config/simple_moveit_controllers.yaml | 12 ++ src/iisy_config/config/stomp_planning.yaml | 39 +++++ .../launch/chomp_planning_pipeline.launch.xml | 23 +++ .../launch/default_warehouse_db.launch | 15 ++ src/iisy_config/launch/demo.launch | 68 ++++++++ src/iisy_config/launch/demo_gazebo.launch | 21 +++ .../fake_moveit_controller_manager.launch.xml | 12 ++ src/iisy_config/launch/gazebo.launch | 32 ++++ .../iisy_moveit_sensor_manager.launch.xml | 3 + .../launch/joystick_control.launch | 17 ++ src/iisy_config/launch/move_group.launch | 101 +++++++++++ src/iisy_config/launch/moveit.rviz | 131 +++++++++++++++ src/iisy_config/launch/moveit_rviz.launch | 15 ++ .../ompl-chomp_planning_pipeline.launch.xml | 19 +++ .../launch/ompl_planning_pipeline.launch.xml | 26 +++ ...otion_planner_planning_pipeline.launch.xml | 15 ++ .../launch/planning_context.launch | 26 +++ .../launch/planning_pipeline.launch.xml | 10 ++ ...ntrol_moveit_controller_manager.launch.xml | 4 + src/iisy_config/launch/ros_controllers.launch | 11 ++ .../launch/run_benchmark_ompl.launch | 21 +++ .../launch/sensor_manager.launch.xml | 17 ++ src/iisy_config/launch/setup_assistant.launch | 16 ++ ...imple_moveit_controller_manager.launch.xml | 8 + .../launch/stomp_planning_pipeline.launch.xml | 25 +++ .../launch/trajectory_execution.launch.xml | 23 +++ src/iisy_config/launch/warehouse.launch | 15 ++ .../launch/warehouse_settings.launch.xml | 16 ++ src/iisy_config/package.xml | 46 +++++ 47 files changed, 1266 insertions(+), 8 deletions(-) delete mode 100644 src/gaz_simulation/.package.xml.kate-swp create mode 100644 src/gaz_simulation/launch/.moveit_launch.py.kate-swp create mode 100644 src/gaz_simulation/launch/moveit_launch.py create mode 100644 src/iisy_config/.setup_assistant create mode 100644 src/iisy_config/CMakeLists.txt create mode 100644 src/iisy_config/config/cartesian_limits.yaml create mode 100644 src/iisy_config/config/chomp_planning.yaml create mode 100644 src/iisy_config/config/fake_controllers.yaml create mode 100644 src/iisy_config/config/gazebo_controllers.yaml create mode 100644 src/iisy_config/config/iisy.srdf create mode 100644 src/iisy_config/config/joint_limits.yaml create mode 100644 src/iisy_config/config/kinematics.yaml create mode 100644 src/iisy_config/config/ompl_planning.yaml create mode 100644 src/iisy_config/config/ros_controllers.yaml create mode 100644 src/iisy_config/config/sensors_3d.yaml create mode 100644 src/iisy_config/config/simple_moveit_controllers.yaml create mode 100644 src/iisy_config/config/stomp_planning.yaml create mode 100644 src/iisy_config/launch/chomp_planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/default_warehouse_db.launch create mode 100644 src/iisy_config/launch/demo.launch create mode 100644 src/iisy_config/launch/demo_gazebo.launch create mode 100644 src/iisy_config/launch/fake_moveit_controller_manager.launch.xml create mode 100644 src/iisy_config/launch/gazebo.launch create mode 100644 src/iisy_config/launch/iisy_moveit_sensor_manager.launch.xml create mode 100644 src/iisy_config/launch/joystick_control.launch create mode 100644 src/iisy_config/launch/move_group.launch create mode 100644 src/iisy_config/launch/moveit.rviz create mode 100644 src/iisy_config/launch/moveit_rviz.launch create mode 100644 src/iisy_config/launch/ompl-chomp_planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/ompl_planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/planning_context.launch create mode 100644 src/iisy_config/launch/planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/ros_control_moveit_controller_manager.launch.xml create mode 100644 src/iisy_config/launch/ros_controllers.launch create mode 100644 src/iisy_config/launch/run_benchmark_ompl.launch create mode 100644 src/iisy_config/launch/sensor_manager.launch.xml create mode 100644 src/iisy_config/launch/setup_assistant.launch create mode 100644 src/iisy_config/launch/simple_moveit_controller_manager.launch.xml create mode 100644 src/iisy_config/launch/stomp_planning_pipeline.launch.xml create mode 100644 src/iisy_config/launch/trajectory_execution.launch.xml create mode 100644 src/iisy_config/launch/warehouse.launch create mode 100644 src/iisy_config/launch/warehouse_settings.launch.xml create mode 100644 src/iisy_config/package.xml diff --git a/src/gaz_simulation/.package.xml.kate-swp b/src/gaz_simulation/.package.xml.kate-swp deleted file mode 100644 index 730b55182ee69fd3c9a0442d771552861ec2d473..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 334 zcmZQzU=Z?7EJ;-eE>A2_aLdd|RWQ;sU|?VnkxySTtK`>w(XX4oE&acJPmyYw{J!8I zpbRe%gFqOF!vkgl4FPeup`1VvhYQLH2XQ!|9NADHgBL{bfCz37!382XU4uashikAW zkP-r7H6UixMexn;MFgJ(#D|&)QqKzIgB-{Y#Ku5u Y;tKX7h-(BALU2L4SrJ^2;VkG}06E_#bpQYW diff --git a/src/gaz_simulation/launch/.moveit_launch.py.kate-swp b/src/gaz_simulation/launch/.moveit_launch.py.kate-swp new file mode 100644 index 0000000000000000000000000000000000000000..de3a6aba4bfd75973b77bde10e65829233d4ab66 GIT binary patch literal 169 zcmZQzU=Z?7EJ;-eE>A2_aLdd|RWQ;sU|?VnS@~1rMv(L2CD;4HUq1LDZ{A_%6&xG{ zl<@;%5a0%Je8Efx24xV(2g;EKalD}%MG(ge%25GvJfR%^P$0t(MEHUT9}wXUBD_GV OJb;)3h`B)`o~{5q?itwt literal 0 HcmV?d00001 diff --git a/src/gaz_simulation/launch/moveit_launch.py b/src/gaz_simulation/launch/moveit_launch.py new file mode 100644 index 0000000..a9f928d --- /dev/null +++ b/src/gaz_simulation/launch/moveit_launch.py @@ -0,0 +1,114 @@ +import os +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import ExecuteProcess, IncludeLaunchDescription +from launch_ros.substitutions import FindPackageShare +from launch.substitutions import Command +from launch.launch_description_sources import PythonLaunchDescriptionSource + +def generate_launch_description(): + robot_name = "iisy" + package_name = "gaz_simulation" + pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros') + path = FindPackageShare(package=package_name).find(package_name) + world_path = os.path.join(path, "world/test2.xml") + urdf_path = os.path.join(path, "urdf/iisy.urdf") + return LaunchDescription([ + #IncludeLaunchDescription( + # PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')), + # launch_arguments={'world': world_path}.items() + #), + + ExecuteProcess( + cmd=[[ + 'LIBGL_ALWAYS_SOFTWARE=true ros2 launch gazebo_ros gzserver.launch.py "world:='+world_path+'"' + ]], + shell=True + ), + + + # Start Gazebo client + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')) + ), + Node( + package='tf2_ros', + namespace='gaz_simulation', + executable='static_transform_publisher', + name='lidar_1_broadcaster', + arguments=["1", "-1.9", "1", "1.5707963267949", "0", "0", "map", "lidar_1_link"] + ), + Node( + package='tf2_ros', + namespace='gaz_simulation', + executable='static_transform_publisher', + name='lidar_2_broadcaster', + arguments=["-1.9", "1", "1", "0", "0", "0", "map", "lidar_2_link"] + ), + Node( + package='gazebo_ros', + executable='spawn_entity.py', + arguments=['-entity', robot_name, + '-topic', 'robot_description', + '-x', '-1', + '-y', '-1', + '-z', '1', + '-Y', '0'], # Yaw + output='screen' + ), + # Subscribe to the joint states of the robot, and publish the 3D pose of each link. + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'robot_description': Command(['xacro ', urdf_path])}] + ), + + # Publish the joint states of the robot + Node( + package='joint_state_publisher', + executable='joint_state_publisher', + name='joint_state_publisher' + ) + + # , + # Node( + # namespace='turtlesim1', + # executable='gazebo', + # name='gazebo', + # arguments=["test.xml"] + # ) + ]) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/gaz_simulation/launch/test_launch.py b/src/gaz_simulation/launch/test_launch.py index 9858884..42f24c6 100644 --- a/src/gaz_simulation/launch/test_launch.py +++ b/src/gaz_simulation/launch/test_launch.py @@ -6,6 +6,7 @@ from launch_ros.substitutions import FindPackageShare from launch.substitutions import Command from launch.launch_description_sources import PythonLaunchDescriptionSource + def generate_launch_description(): robot_name = "iisy" package_name = "gaz_simulation" diff --git a/src/gaz_simulation/package.xml b/src/gaz_simulation/package.xml index 476547c..aecf684 100644 --- a/src/gaz_simulation/package.xml +++ b/src/gaz_simulation/package.xml @@ -7,7 +7,7 @@ ament_cmake - gazebo-11 + gazebo image_transport_plugins robot_state_publisher diff --git a/src/gaz_simulation/urdf/iisy.urdf b/src/gaz_simulation/urdf/iisy.urdf index ea77848..a2b248f 100644 --- a/src/gaz_simulation/urdf/iisy.urdf +++ b/src/gaz_simulation/urdf/iisy.urdf @@ -1,6 +1,6 @@ - + @@ -189,11 +189,6 @@ - - - /simple_model - - transmission_interface/SimpleTransmission @@ -257,7 +252,7 @@ - / + /iisy \ No newline at end of file diff --git a/src/iisy_config/.setup_assistant b/src/iisy_config/.setup_assistant new file mode 100644 index 0000000..696bae9 --- /dev/null +++ b/src/iisy_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: gaz_simulation + relative_path: urdf/iisy.urdf + xacro_args: "" + SRDF: + relative_path: config/iisy.srdf + CONFIG: + author_name: bastian + author_email: bastian.hofmann@xitaso.com + generated_timestamp: 1647313439 \ No newline at end of file diff --git a/src/iisy_config/CMakeLists.txt b/src/iisy_config/CMakeLists.txt new file mode 100644 index 0000000..e09ebc5 --- /dev/null +++ b/src/iisy_config/CMakeLists.txt @@ -0,0 +1,28 @@ +cmake_minimum_required(VERSION 3.8) +project(iisy_config) + +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( REQUIRED) + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) + +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() + +ament_package() diff --git a/src/iisy_config/config/cartesian_limits.yaml b/src/iisy_config/config/cartesian_limits.yaml new file mode 100644 index 0000000..7df72f6 --- /dev/null +++ b/src/iisy_config/config/cartesian_limits.yaml @@ -0,0 +1,5 @@ +cartesian_limits: + max_trans_vel: 1 + max_trans_acc: 2.25 + max_trans_dec: -5 + max_rot_vel: 1.57 diff --git a/src/iisy_config/config/chomp_planning.yaml b/src/iisy_config/config/chomp_planning.yaml new file mode 100644 index 0000000..eb9c912 --- /dev/null +++ b/src/iisy_config/config/chomp_planning.yaml @@ -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.0 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearance: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: false +max_recovery_attempts: 5 diff --git a/src/iisy_config/config/fake_controllers.yaml b/src/iisy_config/config/fake_controllers.yaml new file mode 100644 index 0000000..a97a8f3 --- /dev/null +++ b/src/iisy_config/config/fake_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: fake_iisy_controller + type: $(arg fake_execution_type) + joints: + - base_rot + - base_link1_joint + - link1_link2_joint + - link2_rot + - link2_link3_joint + - link3_rot +initial: # Define initial robot poses per group + - group: iisy + pose: home \ No newline at end of file diff --git a/src/iisy_config/config/gazebo_controllers.yaml b/src/iisy_config/config/gazebo_controllers.yaml new file mode 100644 index 0000000..e4d2eb0 --- /dev/null +++ b/src/iisy_config/config/gazebo_controllers.yaml @@ -0,0 +1,4 @@ +# Publish joint_states +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/src/iisy_config/config/iisy.srdf b/src/iisy_config/config/iisy.srdf new file mode 100644 index 0000000..9296ecc --- /dev/null +++ b/src/iisy_config/config/iisy.srdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/config/joint_limits.yaml b/src/iisy_config/config/joint_limits.yaml new file mode 100644 index 0000000..64ec7c1 --- /dev/null +++ b/src/iisy_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# 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: + base_link1_joint: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 + base_rot: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 + link1_link2_joint: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 + link2_link3_joint: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 + link2_rot: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 + link3_rot: + has_velocity_limits: true + max_velocity: 1.7453292519943 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/src/iisy_config/config/kinematics.yaml b/src/iisy_config/config/kinematics.yaml new file mode 100644 index 0000000..21e35d5 --- /dev/null +++ b/src/iisy_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +iisy: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/src/iisy_config/config/ompl_planning.yaml b/src/iisy_config/config/ompl_planning.yaml new file mode 100644 index 0000000..ff4e5b3 --- /dev/null +++ b/src/iisy_config/config/ompl_planning.yaml @@ -0,0 +1,157 @@ +planner_configs: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: true # Attempt to shortcut all new solution paths + hybridize: true # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +iisy: + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints(base_rot,base_link1_joint) + longest_valid_segment_fraction: 0.005 diff --git a/src/iisy_config/config/ros_controllers.yaml b/src/iisy_config/config/ros_controllers.yaml new file mode 100644 index 0000000..1a50f50 --- /dev/null +++ b/src/iisy_config/config/ros_controllers.yaml @@ -0,0 +1,40 @@ +iisy_controller: + type: effort_controllers/JointTrajectoryController + joints: + - base_rot + - base_link1_joint + - link1_link2_joint + - link2_rot + - link2_link3_joint + - link3_rot + gains: + base_rot: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + base_link1_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + link1_link2_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + link2_rot: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + link2_link3_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + link3_rot: + p: 100 + d: 1 + i: 1 + i_clamp: 1 \ No newline at end of file diff --git a/src/iisy_config/config/sensors_3d.yaml b/src/iisy_config/config/sensors_3d.yaml new file mode 100644 index 0000000..51010a3 --- /dev/null +++ b/src/iisy_config/config/sensors_3d.yaml @@ -0,0 +1,2 @@ +sensors: + [] \ No newline at end of file diff --git a/src/iisy_config/config/simple_moveit_controllers.yaml b/src/iisy_config/config/simple_moveit_controllers.yaml new file mode 100644 index 0000000..d2307c1 --- /dev/null +++ b/src/iisy_config/config/simple_moveit_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: iisy_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: True + joints: + - base_rot + - base_link1_joint + - link1_link2_joint + - link2_rot + - link2_link3_joint + - link3_rot \ No newline at end of file diff --git a/src/iisy_config/config/stomp_planning.yaml b/src/iisy_config/config/stomp_planning.yaml new file mode 100644 index 0000000..2a3d04a --- /dev/null +++ b/src/iisy_config/config/stomp_planning.yaml @@ -0,0 +1,39 @@ +stomp/iisy: + group_name: iisy + optimization: + num_timesteps: 60 + num_iterations: 40 + num_iterations_after_valid: 0 + num_rollouts: 30 + max_rollouts: 30 + initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] + control_cost_weight: 0.0 + task: + noise_generator: + - class: stomp_moveit/NormalDistributionSampling + stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05] + cost_functions: + - class: stomp_moveit/CollisionCheck + collision_penalty: 1.0 + cost_weight: 1.0 + kernel_window_percentage: 0.2 + longest_valid_joint_move: 0.05 + noisy_filters: + - class: stomp_moveit/JointLimits + lock_start: True + lock_goal: True + - class: stomp_moveit/MultiTrajectoryVisualization + line_width: 0.02 + rgb: [255, 255, 0] + marker_array_topic: stomp_trajectories + marker_namespace: noisy + update_filters: + - class: stomp_moveit/PolynomialSmoother + poly_order: 6 + - class: stomp_moveit/TrajectoryVisualization + line_width: 0.05 + rgb: [0, 191, 255] + error_rgb: [255, 0, 0] + publish_intermediate: True + marker_topic: stomp_trajectory + marker_namespace: optimized \ No newline at end of file diff --git a/src/iisy_config/launch/chomp_planning_pipeline.launch.xml b/src/iisy_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..33543cb --- /dev/null +++ b/src/iisy_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/default_warehouse_db.launch b/src/iisy_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..e965b09 --- /dev/null +++ b/src/iisy_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/demo.launch b/src/iisy_config/launch/demo.launch new file mode 100644 index 0000000..4ed05b4 --- /dev/null +++ b/src/iisy_config/launch/demo.launch @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/demo_gazebo.launch b/src/iisy_config/launch/demo_gazebo.launch new file mode 100644 index 0000000..a9f320c --- /dev/null +++ b/src/iisy_config/launch/demo_gazebo.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/fake_moveit_controller_manager.launch.xml b/src/iisy_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..d298e6f --- /dev/null +++ b/src/iisy_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/src/iisy_config/launch/gazebo.launch b/src/iisy_config/launch/gazebo.launch new file mode 100644 index 0000000..494c07f --- /dev/null +++ b/src/iisy_config/launch/gazebo.launch @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/iisy_moveit_sensor_manager.launch.xml b/src/iisy_config/launch/iisy_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/src/iisy_config/launch/iisy_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/src/iisy_config/launch/joystick_control.launch b/src/iisy_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/src/iisy_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/move_group.launch b/src/iisy_config/launch/move_group.launch new file mode 100644 index 0000000..e082c0c --- /dev/null +++ b/src/iisy_config/launch/move_group.launch @@ -0,0 +1,101 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/moveit.rviz b/src/iisy_config/launch/moveit.rviz new file mode 100644 index 0000000..6d87444 --- /dev/null +++ b/src/iisy_config/launch/moveit.rviz @@ -0,0 +1,131 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5 + Tree Height: 226 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Name: MotionPlanning + Planned Path: + Links: ~ + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: ~ + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 2.0 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.75 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.5 + Target Frame: world + Yaw: -0.6232355833053589 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 848 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1291 + X: 454 + Y: 25 diff --git a/src/iisy_config/launch/moveit_rviz.launch b/src/iisy_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..a4605c0 --- /dev/null +++ b/src/iisy_config/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/ompl-chomp_planning_pipeline.launch.xml b/src/iisy_config/launch/ompl-chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..b078992 --- /dev/null +++ b/src/iisy_config/launch/ompl-chomp_planning_pipeline.launch.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + diff --git a/src/iisy_config/launch/ompl_planning_pipeline.launch.xml b/src/iisy_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..2348490 --- /dev/null +++ b/src/iisy_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/src/iisy_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml new file mode 100644 index 0000000..c7c4cf5 --- /dev/null +++ b/src/iisy_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/planning_context.launch b/src/iisy_config/launch/planning_context.launch new file mode 100644 index 0000000..cf28d5f --- /dev/null +++ b/src/iisy_config/launch/planning_context.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/planning_pipeline.launch.xml b/src/iisy_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..4b4d0d6 --- /dev/null +++ b/src/iisy_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/src/iisy_config/launch/ros_control_moveit_controller_manager.launch.xml b/src/iisy_config/launch/ros_control_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..9ebc91c --- /dev/null +++ b/src/iisy_config/launch/ros_control_moveit_controller_manager.launch.xml @@ -0,0 +1,4 @@ + + + + diff --git a/src/iisy_config/launch/ros_controllers.launch b/src/iisy_config/launch/ros_controllers.launch new file mode 100644 index 0000000..2decb91 --- /dev/null +++ b/src/iisy_config/launch/ros_controllers.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/src/iisy_config/launch/run_benchmark_ompl.launch b/src/iisy_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..7b49cf7 --- /dev/null +++ b/src/iisy_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/sensor_manager.launch.xml b/src/iisy_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..e91b5c3 --- /dev/null +++ b/src/iisy_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/setup_assistant.launch b/src/iisy_config/launch/setup_assistant.launch new file mode 100644 index 0000000..700a33b --- /dev/null +++ b/src/iisy_config/launch/setup_assistant.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + diff --git a/src/iisy_config/launch/simple_moveit_controller_manager.launch.xml b/src/iisy_config/launch/simple_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..3a962b2 --- /dev/null +++ b/src/iisy_config/launch/simple_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/src/iisy_config/launch/stomp_planning_pipeline.launch.xml b/src/iisy_config/launch/stomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..805ad25 --- /dev/null +++ b/src/iisy_config/launch/stomp_planning_pipeline.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/trajectory_execution.launch.xml b/src/iisy_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..20c3dfc --- /dev/null +++ b/src/iisy_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/warehouse.launch b/src/iisy_config/launch/warehouse.launch new file mode 100644 index 0000000..0712e67 --- /dev/null +++ b/src/iisy_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/src/iisy_config/launch/warehouse_settings.launch.xml b/src/iisy_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/src/iisy_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/src/iisy_config/package.xml b/src/iisy_config/package.xml new file mode 100644 index 0000000..c29adac --- /dev/null +++ b/src/iisy_config/package.xml @@ -0,0 +1,46 @@ + + + + iisy_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the iisy with the MoveIt Motion Planning Framework + + bastian + bastian + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + ament_cmake + + rclcpp + moveit_ros_move_group + + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz2 + tf2_ros + xacro + + + + + + gaz_simulation + + + ament_cmake + + +