From 375a83599ac4fc16660a317a74fec74175c34ce5 Mon Sep 17 00:00:00 2001 From: ZacZhangzhuo Date: Sun, 4 Jun 2023 15:02:17 +0200 Subject: [PATCH 1/3] init --- .setup_assistant | 28 ++- .vscode/c_cpp_properties.json | 184 ++++++++++++++++++ CMakeLists.txt | 11 +- README.md | 2 +- config/abb_crb15000_5_95.ros2_control.xacro | 56 ++++++ config/abb_crb15000_5_95.srdf | 17 ++ config/abb_crb15000_5_95.urdf.xacro | 14 ++ config/cartesian_limits.yaml | 5 - config/chomp_planning.yaml | 18 -- config/fake_controllers.yaml | 15 -- config/gazebo_controllers.yaml | 4 - config/initial_positions.yaml | 9 + config/joint_limits.yaml | 12 +- config/kinematics.yaml | 4 +- config/moveit.rviz | 51 +++++ config/moveit_controllers.yaml | 21 ++ config/ompl_planning.yaml | 158 --------------- config/pilz_cartesian_limits.yaml | 6 + config/ros2_controllers.yaml | 26 +++ config/ros_controllers.yaml | 0 config/sensors_3d.yaml | 2 - config/simple_moveit_controllers.yaml | 2 - config/stomp_planning.yaml | 39 ---- ...5000_5_95_moveit_sensor_manager.launch.xml | 3 - launch/chomp_planning_pipeline.launch.xml | 23 --- launch/default_warehouse_db.launch | 15 -- launch/demo.launch | 69 ------- launch/demo.launch.py | 7 + launch/demo_gazebo.launch | 21 -- .../fake_moveit_controller_manager.launch.xml | 12 -- launch/gazebo.launch | 32 --- launch/joystick_control.launch | 17 -- launch/move_group.launch | 101 ---------- launch/move_group.launch.py | 7 + launch/moveit.rviz | 131 ------------- launch/moveit_rviz.launch | 15 -- launch/moveit_rviz.launch.py | 7 + .../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 - launch/ros_controllers.launch | 11 -- launch/rsp.launch.py | 7 + launch/run_benchmark_ompl.launch | 21 -- launch/sensor_manager.launch.xml | 17 -- launch/setup_assistant.launch | 16 -- launch/setup_assistant.launch.py | 7 + ...imple_moveit_controller_manager.launch.xml | 8 - launch/spawn_controllers.launch.py | 7 + launch/static_virtual_joint_tfs.launch.py | 7 + launch/stomp_planning_pipeline.launch.xml | 25 --- launch/trajectory_execution.launch.xml | 23 --- launch/warehouse.launch | 15 -- launch/warehouse_db.launch.py | 7 + launch/warehouse_settings.launch.xml | 16 -- package.xml | 64 +++--- 58 files changed, 513 insertions(+), 982 deletions(-) create mode 100644 .vscode/c_cpp_properties.json create mode 100644 config/abb_crb15000_5_95.ros2_control.xacro create mode 100644 config/abb_crb15000_5_95.urdf.xacro delete mode 100644 config/cartesian_limits.yaml delete mode 100644 config/chomp_planning.yaml delete mode 100644 config/fake_controllers.yaml delete mode 100644 config/gazebo_controllers.yaml create mode 100644 config/initial_positions.yaml create mode 100644 config/moveit.rviz create mode 100644 config/moveit_controllers.yaml delete mode 100644 config/ompl_planning.yaml create mode 100644 config/pilz_cartesian_limits.yaml create mode 100644 config/ros2_controllers.yaml delete mode 100644 config/ros_controllers.yaml delete mode 100644 config/sensors_3d.yaml delete mode 100644 config/simple_moveit_controllers.yaml delete mode 100644 config/stomp_planning.yaml delete mode 100644 launch/abb_crb15000_5_95_moveit_sensor_manager.launch.xml delete mode 100644 launch/chomp_planning_pipeline.launch.xml delete mode 100644 launch/default_warehouse_db.launch delete mode 100644 launch/demo.launch create mode 100644 launch/demo.launch.py delete mode 100644 launch/demo_gazebo.launch delete mode 100644 launch/fake_moveit_controller_manager.launch.xml delete mode 100644 launch/gazebo.launch delete mode 100644 launch/joystick_control.launch delete mode 100644 launch/move_group.launch create mode 100644 launch/move_group.launch.py delete mode 100644 launch/moveit.rviz delete mode 100644 launch/moveit_rviz.launch create mode 100644 launch/moveit_rviz.launch.py delete mode 100644 launch/ompl-chomp_planning_pipeline.launch.xml delete mode 100644 launch/ompl_planning_pipeline.launch.xml delete mode 100644 launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml delete mode 100644 launch/planning_context.launch delete mode 100644 launch/planning_pipeline.launch.xml delete mode 100644 launch/ros_control_moveit_controller_manager.launch.xml delete mode 100644 launch/ros_controllers.launch create mode 100644 launch/rsp.launch.py delete mode 100644 launch/run_benchmark_ompl.launch delete mode 100644 launch/sensor_manager.launch.xml delete mode 100644 launch/setup_assistant.launch create mode 100644 launch/setup_assistant.launch.py delete mode 100644 launch/simple_moveit_controller_manager.launch.xml create mode 100644 launch/spawn_controllers.launch.py create mode 100644 launch/static_virtual_joint_tfs.launch.py delete mode 100644 launch/stomp_planning_pipeline.launch.xml delete mode 100644 launch/trajectory_execution.launch.xml delete mode 100644 launch/warehouse.launch create mode 100644 launch/warehouse_db.launch.py delete mode 100644 launch/warehouse_settings.launch.xml diff --git a/.setup_assistant b/.setup_assistant index f110fcb..e013cd1 100644 --- a/.setup_assistant +++ b/.setup_assistant @@ -1,11 +1,25 @@ moveit_setup_assistant_config: - URDF: + urdf: package: abb_crb15000_support relative_path: urdf/crb15000_5_95.xacro - xacro_args: "" - SRDF: + srdf: relative_path: config/abb_crb15000_5_95.srdf - CONFIG: - author_name: Gonzalo Casas - author_email: casas@arch.ethz.ch - generated_timestamp: 1648849764 \ No newline at end of file + package_settings: + author_name: Zac Zhuo Zhang + author_email: zhuzhang@student.ethz.ch + generated_timestamp: 1685881861 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..0344b15 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,184 @@ +{ + "configurations": [ + { + "browse": { + "databaseFilename": "${default}", + "limitSymbolsToIncludedHeaders": false + }, + "includePath": [ + "/home/zac/ws_moveit2/install/pilz_industrial_motion_planner_testutils/include/**", + "/home/zac/ws_moveit2/install/pilz_industrial_motion_planner/include/**", + "/home/zac/ws_moveit2/install/moveit_visual_tools/include/**", + "/home/zac/ws_moveit2/install/moveit_task_constructor_visualization/include/**", + "/home/zac/ws_moveit2/install/moveit_task_constructor_demo/include/**", + "/home/zac/ws_moveit2/install/moveit_task_constructor_core/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_control_interface/include/**", + "/home/zac/ws_moveit2/install/moveit_simple_controller_manager/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_assistant/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_srdf_plugins/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_core_plugins/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_controllers/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_app_plugins/include/**", + "/home/zac/ws_moveit2/install/moveit_setup_framework/include/**", + "/home/zac/ws_moveit2/install/moveit_servo/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_visualization/include/**", + "/home/zac/ws_moveit2/install/moveit_hybrid_planning/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_planning_interface/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_benchmarks/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_warehouse/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_robot_interaction/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_perception/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_move_group/include/**", + "/home/zac/ws_moveit2/install/moveit_planners_ompl/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_planning/include/**", + "/home/zac/ws_moveit2/install/moveit_ros_occupancy_map_monitor/include/**", + "/home/zac/ws_moveit2/install/moveit_kinematics/include/**", + "/home/zac/ws_moveit2/install/chomp_motion_planner/include/**", + "/home/zac/ws_moveit2/install/moveit_core/include/**", + "/home/zac/ws_moveit2/install/srdfdom/include/**", + "/home/zac/ws_moveit2/install/rviz_marker_tools/include/**", + "/home/zac/ws_moveit2/install/rosparam_shortcuts/include/**", + "/home/zac/ws_moveit2/install/moveit_task_constructor_msgs/include/**", + "/opt/ros/humble/include/**", + "/home/zac/ros2_humble/install/rosbag2_compression_zstd/include/**", + "/home/zac/ros2_humble/install/mcap_vendor/include/**", + "/home/zac/ros2_humble/install/rviz_visual_testing_framework/include/**", + "/home/zac/ros2_humble/install/rviz_default_plugins/include/**", + "/home/zac/ros2_humble/install/rviz_common/include/**", + "/home/zac/ros2_humble/install/rosbag2_transport/include/**", + "/home/zac/ros2_humble/install/rosbag2_compression/include/**", + "/home/zac/ros2_humble/install/rosbag2_cpp/include/**", + "/home/zac/ros2_humble/install/rosbag2_storage_default_plugins/include/**", + "/home/zac/ros2_humble/install/rosbag2_storage/include/**", + "/home/zac/ros2_humble/install/camera_info_manager/include/**", + "/home/zac/ros2_humble/install/camera_calibration_parsers/include/**", + "/home/zac/ros2_humble/install/interactive_markers/include/**", + "/home/zac/ros2_humble/install/visualization_msgs/include/**", + "/home/zac/ros2_humble/install/robot_state_publisher/include/**", + "/home/zac/ros2_humble/install/kdl_parser/include/**", + "/home/zac/ros2_humble/install/urdf/include/**", + "/home/zac/ros2_humble/install/urdf_parser_plugin/include/**", + "/home/zac/ros2_humble/install/turtlesim/include/**", + "/home/zac/ros2_humble/install/tf2_sensor_msgs/include/**", + "/home/zac/ros2_humble/install/tf2_kdl/include/**", + "/home/zac/ros2_humble/install/tf2_geometry_msgs/include/**", + "/home/zac/ros2_humble/install/tf2_eigen/include/**", + "/home/zac/ros2_humble/install/tf2_bullet/include/**", + "/home/zac/ros2_humble/install/tf2_ros/include/**", + "/home/zac/ros2_humble/install/tf2_msgs/include/**", + "/home/zac/ros2_humble/install/test_msgs/include/**", + "/home/zac/ros2_humble/install/ros2cli_test_interfaces/include/**", + "/home/zac/ros2_humble/install/image_transport/include/**", + "/home/zac/ros2_humble/install/message_filters/include/**", + "/home/zac/ros2_humble/install/laser_geometry/include/**", + "/home/zac/ros2_humble/install/rclcpp_action/include/**", + "/home/zac/ros2_humble/install/rcl_action/include/**", + "/home/zac/ros2_humble/install/example_interfaces/include/**", + "/home/zac/ros2_humble/install/action_tutorials_interfaces/include/**", + "/home/zac/ros2_humble/install/action_msgs/include/**", + "/home/zac/ros2_humble/install/unique_identifier_msgs/include/**", + "/home/zac/ros2_humble/install/trajectory_msgs/include/**", + "/home/zac/ros2_humble/install/tlsf_cpp/include/**", + "/home/zac/ros2_humble/install/rqt_gui_cpp/include/**", + "/home/zac/ros2_humble/install/rosbag2_test_common/include/**", + "/home/zac/ros2_humble/install/rclcpp_lifecycle/include/**", + "/home/zac/ros2_humble/install/logging_demo/include/**", + "/home/zac/ros2_humble/install/image_tools/include/**", + "/home/zac/ros2_humble/install/rclcpp_components/include/**", + "/home/zac/ros2_humble/install/intra_process_demo/include/**", + "/home/zac/ros2_humble/install/examples_rclcpp_cbg_executor/include/**", + "/home/zac/ros2_humble/install/rclcpp/include/**", + "/home/zac/ros2_humble/install/rcl_lifecycle/include/**", + "/home/zac/ros2_humble/install/libstatistics_collector/include/**", + "/home/zac/ros2_humble/install/rcl/include/**", + "/home/zac/ros2_humble/install/rmw_fastrtps_dynamic_cpp/include/**", + "/home/zac/ros2_humble/install/rmw_fastrtps_cpp/include/**", + "/home/zac/ros2_humble/install/rmw_fastrtps_shared_cpp/include/**", + "/home/zac/ros2_humble/install/tracetools/include/**", + "/home/zac/ros2_humble/install/tlsf/include/**", + "/home/zac/ros2_humble/install/qt_gui_cpp/include/**", + "/home/zac/ros2_humble/install/pluginlib/include/**", + "/home/zac/ros2_humble/install/tf2_eigen_kdl/include/**", + "/home/zac/ros2_humble/install/tf2/include/**", + "/home/zac/ros2_humble/install/stereo_msgs/include/**", + "/home/zac/ros2_humble/install/std_srvs/include/**", + "/home/zac/ros2_humble/install/shape_msgs/include/**", + "/home/zac/ros2_humble/install/map_msgs/include/**", + "/home/zac/ros2_humble/install/sensor_msgs/include/**", + "/home/zac/ros2_humble/install/nav_msgs/include/**", + "/home/zac/ros2_humble/install/diagnostic_msgs/include/**", + "/home/zac/ros2_humble/install/geometry_msgs/include/**", + "/home/zac/ros2_humble/install/actionlib_msgs/include/**", + "/home/zac/ros2_humble/install/std_msgs/include/**", + "/home/zac/ros2_humble/install/statistics_msgs/include/**", + "/home/zac/ros2_humble/install/shared_queues_vendor/include/**", + "/home/zac/ros2_humble/install/rviz_rendering/include/**", + "/home/zac/ros2_humble/install/rttest/include/**", + "/home/zac/ros2_humble/install/rmw_connextdds_common/include/**", + "/home/zac/ros2_humble/install/rosgraph_msgs/include/**", + "/home/zac/ros2_humble/install/rosbag2_interfaces/include/**", + "/home/zac/ros2_humble/install/rmw_dds_common/include/**", + "/home/zac/ros2_humble/install/composition_interfaces/include/**", + "/home/zac/ros2_humble/install/rcl_interfaces/include/**", + "/home/zac/ros2_humble/install/pendulum_msgs/include/**", + "/home/zac/ros2_humble/install/lifecycle_msgs/include/**", + "/home/zac/ros2_humble/install/builtin_interfaces/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_cpp/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_introspection_cpp/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_c/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_introspection_c/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_fastrtps_c/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_fastrtps_cpp/include/**", + "/home/zac/ros2_humble/install/rosidl_runtime_cpp/include/**", + "/home/zac/ros2_humble/install/rcl_yaml_param_parser/include/**", + "/home/zac/ros2_humble/install/rmw/include/**", + "/home/zac/ros2_humble/install/rosidl_runtime_c/include/**", + "/home/zac/ros2_humble/install/rosidl_typesupport_interface/include/**", + "/home/zac/ros2_humble/install/rosbag2_storage_mcap_testdata/include/**", + "/home/zac/ros2_humble/install/resource_retriever/include/**", + "/home/zac/ros2_humble/install/class_loader/include/**", + "/home/zac/ros2_humble/install/rcpputils/include/**", + "/home/zac/ros2_humble/install/rcl_logging_interface/include/**", + "/home/zac/ros2_humble/install/rcutils/include/**", + "/home/zac/ros2_humble/install/performance_test_fixture/include/**", + "/home/zac/ros2_humble/install/mimick_vendor/include/**", + "/home/zac/ros2_humble/install/libyaml_vendor/include/**", + "/home/zac/ros2_humble/install/keyboard_handler/include/**", + "/home/zac/ros2_humble/install/ament_index_cpp/include/**", + "/home/zac/ws_moveit2/src/hello_moveit/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_interface/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_motion_planner/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner_testutils/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_plugins/moveit_ros_control_interface/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_plugins/moveit_simple_controller_manager/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/benchmarks/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/move_group/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/moveit_servo/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/occupancy_map_monitor/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/robot_interaction/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_ros/warehouse/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_app_plugins/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_assistant/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_controllers/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_core_plugins/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_framework/include/**", + "/home/zac/ws_moveit2/src/moveit2/moveit_setup_assistant/moveit_setup_srdf_plugins/include/**", + "/home/zac/ws_moveit2/src/moveit_task_constructor/core/include/**", + "/home/zac/ws_moveit2/src/moveit_task_constructor/demo/include/**", + "/home/zac/ws_moveit2/src/moveit_task_constructor/rviz_marker_tools/include/**", + "/home/zac/ws_moveit2/src/moveit_visual_tools/include/**", + "/home/zac/ws_moveit2/src/rosparam_shortcuts/include/**", + "/home/zac/ws_moveit2/src/srdfdom/include/**", + "/usr/include/**" + ], + "name": "ROS", + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/gcc", + "cStandard": "gnu11", + "cppStandard": "c++14" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index d4e8dd4..e7eaceb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,11 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 3.22) project(abb_crb15000_5_95_moveit_config) -find_package(catkin REQUIRED) +find_package(ament_cmake REQUIRED) -catkin_package() +ament_package() -install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} PATTERN "setup_assistant.launch" EXCLUDE) -install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/README.md b/README.md index a538f1b..bf5fb8c 100644 --- a/README.md +++ b/README.md @@ -1 +1 @@ -# abb_crb15000_5_95_moveit_config +# abb_crb15000_5_95_moveit_config \ No newline at end of file diff --git a/config/abb_crb15000_5_95.ros2_control.xacro b/config/abb_crb15000_5_95.ros2_control.xacro new file mode 100644 index 0000000..06899d0 --- /dev/null +++ b/config/abb_crb15000_5_95.ros2_control.xacro @@ -0,0 +1,56 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['joint_1']} + + + + + + + ${initial_positions['joint_2']} + + + + + + + ${initial_positions['joint_3']} + + + + + + + ${initial_positions['joint_4']} + + + + + + + ${initial_positions['joint_5']} + + + + + + + ${initial_positions['joint_6']} + + + + + + + diff --git a/config/abb_crb15000_5_95.srdf b/config/abb_crb15000_5_95.srdf index 3f85756..380535d 100644 --- a/config/abb_crb15000_5_95.srdf +++ b/config/abb_crb15000_5_95.srdf @@ -12,6 +12,23 @@ + + + + + + + + + + + + + + + + + diff --git a/config/abb_crb15000_5_95.urdf.xacro b/config/abb_crb15000_5_95.urdf.xacro new file mode 100644 index 0000000..47a9acf --- /dev/null +++ b/config/abb_crb15000_5_95.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/config/cartesian_limits.yaml b/config/cartesian_limits.yaml deleted file mode 100644 index 7df72f6..0000000 --- a/config/cartesian_limits.yaml +++ /dev/null @@ -1,5 +0,0 @@ -cartesian_limits: - max_trans_vel: 1 - max_trans_acc: 2.25 - max_trans_dec: -5 - max_rot_vel: 1.57 diff --git a/config/chomp_planning.yaml b/config/chomp_planning.yaml deleted file mode 100644 index eb9c912..0000000 --- a/config/chomp_planning.yaml +++ /dev/null @@ -1,18 +0,0 @@ -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/config/fake_controllers.yaml b/config/fake_controllers.yaml deleted file mode 100644 index 5a7cbcd..0000000 --- a/config/fake_controllers.yaml +++ /dev/null @@ -1,15 +0,0 @@ -controller_list: - - name: fake_manipulator_controller - type: $(arg fake_execution_type) - joints: - - joint_1 - - joint_2 - - joint_3 - - joint_4 - - joint_5 - - joint_6 -initial: # Define initial robot poses per group -# - group: manipulator -# pose: home - - [] \ No newline at end of file diff --git a/config/gazebo_controllers.yaml b/config/gazebo_controllers.yaml deleted file mode 100644 index e4d2eb0..0000000 --- a/config/gazebo_controllers.yaml +++ /dev/null @@ -1,4 +0,0 @@ -# Publish joint_states -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 diff --git a/config/initial_positions.yaml b/config/initial_positions.yaml new file mode 100644 index 0000000..0eb43b5 --- /dev/null +++ b/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for abb_crb15000_5_95's ros2_control fake system + +initial_positions: + joint_1: 0 + joint_2: 0 + joint_3: 0 + joint_4: 0 + joint_5: 0 + joint_6: 0 \ No newline at end of file diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml index 5b9781f..92f9b44 100644 --- a/config/joint_limits.yaml +++ b/config/joint_limits.yaml @@ -10,31 +10,31 @@ default_acceleration_scaling_factor: 0.1 joint_limits: joint_1: has_velocity_limits: true - max_velocity: 2.181661564992912 + max_velocity: 2.1816615649929121 has_acceleration_limits: false max_acceleration: 0 joint_2: has_velocity_limits: true - max_velocity: 2.181661564992912 + max_velocity: 2.1816615649929121 has_acceleration_limits: false max_acceleration: 0 joint_3: has_velocity_limits: true - max_velocity: 2.443460952792061 + max_velocity: 2.4434609527920612 has_acceleration_limits: false max_acceleration: 0 joint_4: has_velocity_limits: true - max_velocity: 3.490658503988659 + max_velocity: 3.4906585039886591 has_acceleration_limits: false max_acceleration: 0 joint_5: has_velocity_limits: true - max_velocity: 3.490658503988659 + max_velocity: 3.4906585039886591 has_acceleration_limits: false max_acceleration: 0 joint_6: has_velocity_limits: true - max_velocity: 3.490658503988659 + max_velocity: 3.4906585039886591 has_acceleration_limits: false max_acceleration: 0 \ No newline at end of file diff --git a/config/kinematics.yaml b/config/kinematics.yaml index ad478ed..bcc4162 100644 --- a/config/kinematics.yaml +++ b/config/kinematics.yaml @@ -1,4 +1,4 @@ manipulator: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 \ No newline at end of file + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/config/moveit.rviz b/config/moveit.rviz new file mode 100644 index 0000000..99bb740 --- /dev/null +++ b/config/moveit.rviz @@ -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: base_link + 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: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/config/moveit_controllers.yaml b/config/moveit_controllers.yaml new file mode 100644 index 0000000..f37c6b5 --- /dev/null +++ b/config/moveit_controllers.yaml @@ -0,0 +1,21 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - arm_controller + + arm_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 + action_ns: follow_joint_trajectory + default: true \ No newline at end of file diff --git a/config/ompl_planning.yaml b/config/ompl_planning.yaml deleted file mode 100644 index 96d2a41..0000000 --- a/config/ompl_planning.yaml +++ /dev/null @@ -1,158 +0,0 @@ -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 -manipulator: - default_planner_config: RRTstar - 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(joint_1,joint_2) - longest_valid_segment_fraction: 0.005 diff --git a/config/pilz_cartesian_limits.yaml b/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..b2997ca --- /dev/null +++ b/config/pilz_cartesian_limits.yaml @@ -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 diff --git a/config/ros2_controllers.yaml b/config/ros2_controllers.yaml new file mode 100644 index 0000000..5ce31f4 --- /dev/null +++ b/config/ros2_controllers.yaml @@ -0,0 +1,26 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + abb_arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +abb_arm_controller: + ros__parameters: + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 + command_interfaces: + - position + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/config/ros_controllers.yaml b/config/ros_controllers.yaml deleted file mode 100644 index e69de29..0000000 diff --git a/config/sensors_3d.yaml b/config/sensors_3d.yaml deleted file mode 100644 index 51010a3..0000000 --- a/config/sensors_3d.yaml +++ /dev/null @@ -1,2 +0,0 @@ -sensors: - [] \ No newline at end of file diff --git a/config/simple_moveit_controllers.yaml b/config/simple_moveit_controllers.yaml deleted file mode 100644 index 4118c3b..0000000 --- a/config/simple_moveit_controllers.yaml +++ /dev/null @@ -1,2 +0,0 @@ -controller_list: - [] \ No newline at end of file diff --git a/config/stomp_planning.yaml b/config/stomp_planning.yaml deleted file mode 100644 index 5484a97..0000000 --- a/config/stomp_planning.yaml +++ /dev/null @@ -1,39 +0,0 @@ -stomp/manipulator: - group_name: manipulator - 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/launch/abb_crb15000_5_95_moveit_sensor_manager.launch.xml b/launch/abb_crb15000_5_95_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698..0000000 --- a/launch/abb_crb15000_5_95_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/launch/chomp_planning_pipeline.launch.xml b/launch/chomp_planning_pipeline.launch.xml deleted file mode 100644 index 26136aa..0000000 --- a/launch/chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/launch/default_warehouse_db.launch b/launch/default_warehouse_db.launch deleted file mode 100644 index c4e9ef8..0000000 --- a/launch/default_warehouse_db.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/launch/demo.launch b/launch/demo.launch deleted file mode 100644 index 41bdd12..0000000 --- a/launch/demo.launch +++ /dev/null @@ -1,69 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - - - - [move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/demo.launch.py b/launch/demo.launch.py new file mode 100644 index 0000000..66c7ac0 --- /dev/null +++ b/launch/demo.launch.py @@ -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("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/launch/demo_gazebo.launch b/launch/demo_gazebo.launch deleted file mode 100644 index a9f320c..0000000 --- a/launch/demo_gazebo.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/fake_moveit_controller_manager.launch.xml b/launch/fake_moveit_controller_manager.launch.xml deleted file mode 100644 index a4a78b0..0000000 --- a/launch/fake_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/launch/gazebo.launch b/launch/gazebo.launch deleted file mode 100644 index 9d6bdc9..0000000 --- a/launch/gazebo.launch +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/joystick_control.launch b/launch/joystick_control.launch deleted file mode 100644 index 9411f6e..0000000 --- a/launch/joystick_control.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/launch/move_group.launch b/launch/move_group.launch deleted file mode 100644 index 17c1341..0000000 --- a/launch/move_group.launch +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/move_group.launch.py b/launch/move_group.launch.py new file mode 100644 index 0000000..dde8008 --- /dev/null +++ b/launch/move_group.launch.py @@ -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("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/launch/moveit.rviz b/launch/moveit.rviz deleted file mode 100644 index 6a876dd..0000000 --- a/launch/moveit.rviz +++ /dev/null @@ -1,131 +0,0 @@ -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: base_link - 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: base_link - 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/launch/moveit_rviz.launch b/launch/moveit_rviz.launch deleted file mode 100644 index a4605c0..0000000 --- a/launch/moveit_rviz.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/launch/moveit_rviz.launch.py b/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..4c432b7 --- /dev/null +++ b/launch/moveit_rviz.launch.py @@ -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("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/launch/ompl-chomp_planning_pipeline.launch.xml b/launch/ompl-chomp_planning_pipeline.launch.xml deleted file mode 100644 index b078992..0000000 --- a/launch/ompl-chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - diff --git a/launch/ompl_planning_pipeline.launch.xml b/launch/ompl_planning_pipeline.launch.xml deleted file mode 100644 index 7b8a72a..0000000 --- a/launch/ompl_planning_pipeline.launch.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml deleted file mode 100644 index c7c4cf5..0000000 --- a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/launch/planning_context.launch b/launch/planning_context.launch deleted file mode 100644 index c8817df..0000000 --- a/launch/planning_context.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/planning_pipeline.launch.xml b/launch/planning_pipeline.launch.xml deleted file mode 100644 index 4b4d0d6..0000000 --- a/launch/planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/launch/ros_control_moveit_controller_manager.launch.xml b/launch/ros_control_moveit_controller_manager.launch.xml deleted file mode 100644 index 9ebc91c..0000000 --- a/launch/ros_control_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/launch/ros_controllers.launch b/launch/ros_controllers.launch deleted file mode 100644 index 37e6465..0000000 --- a/launch/ros_controllers.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/launch/rsp.launch.py b/launch/rsp.launch.py new file mode 100644 index 0000000..dde7fb7 --- /dev/null +++ b/launch/rsp.launch.py @@ -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("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/launch/run_benchmark_ompl.launch b/launch/run_benchmark_ompl.launch deleted file mode 100644 index 067079e..0000000 --- a/launch/run_benchmark_ompl.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/sensor_manager.launch.xml b/launch/sensor_manager.launch.xml deleted file mode 100644 index 8090705..0000000 --- a/launch/sensor_manager.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/launch/setup_assistant.launch b/launch/setup_assistant.launch deleted file mode 100644 index 4437139..0000000 --- a/launch/setup_assistant.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - diff --git a/launch/setup_assistant.launch.py b/launch/setup_assistant.launch.py new file mode 100644 index 0000000..0dd8767 --- /dev/null +++ b/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/launch/simple_moveit_controller_manager.launch.xml b/launch/simple_moveit_controller_manager.launch.xml deleted file mode 100644 index f202377..0000000 --- a/launch/simple_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/launch/spawn_controllers.launch.py b/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..1767365 --- /dev/null +++ b/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/launch/static_virtual_joint_tfs.launch.py b/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..8a2f57e --- /dev/null +++ b/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/launch/stomp_planning_pipeline.launch.xml b/launch/stomp_planning_pipeline.launch.xml deleted file mode 100644 index 2d1ca5a..0000000 --- a/launch/stomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/launch/trajectory_execution.launch.xml b/launch/trajectory_execution.launch.xml deleted file mode 100644 index 20c3dfc..0000000 --- a/launch/trajectory_execution.launch.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/warehouse.launch b/launch/warehouse.launch deleted file mode 100644 index 0712e67..0000000 --- a/launch/warehouse.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/launch/warehouse_db.launch.py b/launch/warehouse_db.launch.py new file mode 100644 index 0000000..f66a044 --- /dev/null +++ b/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/launch/warehouse_settings.launch.xml b/launch/warehouse_settings.launch.xml deleted file mode 100644 index e473b08..0000000 --- a/launch/warehouse_settings.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/package.xml b/package.xml index fc23952..9863b15 100644 --- a/package.xml +++ b/package.xml @@ -1,41 +1,51 @@ - - + + + abb_crb15000_5_95_moveit_config 0.3.0 An automatically generated package with all the configuration and launch files for using the abb_crb15000_5_95 with the MoveIt Motion Planning Framework - Gonzalo Casas - Gonzalo Casas + + Zac Zhuo Zhang BSD http://moveit.ros.org/ - https://github.com/ros-planning/moveit/issues - https://github.com/ros-planning/moveit + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Zac Zhuo Zhang - catkin + ament_cmake - moveit_ros_move_group - moveit_fake_controller_manager - 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 - rviz - tf2_ros - xacro + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro - - - - - abb_crb15000_support - - + + + abb_crb15000_support + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + ament_cmake + From 3039c9e7ee32784ed9bab3e634e91a209fc0193b Mon Sep 17 00:00:00 2001 From: Zac Zhang Date: Sun, 4 Jun 2023 15:20:14 +0200 Subject: [PATCH 2/3] init --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index bf5fb8c..35d3ad5 100644 --- a/README.md +++ b/README.md @@ -1 +1,3 @@ -# abb_crb15000_5_95_moveit_config \ No newline at end of file +# abb_crb15000_5_95_moveit_config + +ROS2 package. \ No newline at end of file From c07c317547af7ac03d0e86698e941462febf21ec Mon Sep 17 00:00:00 2001 From: ZacZhangzhuo Date: Sun, 11 Jun 2023 22:41:28 +0200 Subject: [PATCH 3/3] 1.0.1 --- .setup_assistant | 11 ++++--- config/abb_crb15000_5_95.urdf.xacro | 14 --------- ... => abb_irb4600_40_255.ros2_control.xacro} | 7 +++-- ...5000_5_95.srdf => abb_irb4600_40_255.srdf} | 31 +++++++------------ config/abb_irb4600_40_255.urdf.xacro | 14 +++++++++ config/initial_positions.yaml | 2 +- config/joint_limits.yaml | 12 +++---- config/kinematics.yaml | 4 +++ config/moveit_controllers.yaml | 8 ++--- config/ros2_controllers.yaml | 4 +-- launch/demo.launch.py | 2 +- launch/move_group.launch.py | 2 +- launch/moveit_rviz.launch.py | 2 +- launch/rsp.launch.py | 2 +- launch/setup_assistant.launch.py | 2 +- launch/spawn_controllers.launch.py | 2 +- launch/static_virtual_joint_tfs.launch.py | 2 +- launch/warehouse_db.launch.py | 2 +- package.xml | 9 +++--- 19 files changed, 65 insertions(+), 67 deletions(-) delete mode 100644 config/abb_crb15000_5_95.urdf.xacro rename config/{abb_crb15000_5_95.ros2_control.xacro => abb_irb4600_40_255.ros2_control.xacro} (87%) rename config/{abb_crb15000_5_95.srdf => abb_irb4600_40_255.srdf} (70%) create mode 100644 config/abb_irb4600_40_255.urdf.xacro diff --git a/.setup_assistant b/.setup_assistant index e013cd1..b89863c 100644 --- a/.setup_assistant +++ b/.setup_assistant @@ -1,13 +1,14 @@ moveit_setup_assistant_config: urdf: - package: abb_crb15000_support - relative_path: urdf/crb15000_5_95.xacro + package: abb_irb4600_40_255 + relative_path: urdf/abb_irb4600_40_255.urdf + xacro_args: "--inorder " srdf: - relative_path: config/abb_crb15000_5_95.srdf + relative_path: config/abb_irb4600_40_255.srdf package_settings: - author_name: Zac Zhuo Zhang + author_name: Zhu Zhang author_email: zhuzhang@student.ethz.ch - generated_timestamp: 1685881861 + generated_timestamp: 1686503172 control_xacro: command: - position diff --git a/config/abb_crb15000_5_95.urdf.xacro b/config/abb_crb15000_5_95.urdf.xacro deleted file mode 100644 index 47a9acf..0000000 --- a/config/abb_crb15000_5_95.urdf.xacro +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/config/abb_crb15000_5_95.ros2_control.xacro b/config/abb_irb4600_40_255.ros2_control.xacro similarity index 87% rename from config/abb_crb15000_5_95.ros2_control.xacro rename to config/abb_irb4600_40_255.ros2_control.xacro index 06899d0..cb15004 100644 --- a/config/abb_crb15000_5_95.ros2_control.xacro +++ b/config/abb_irb4600_40_255.ros2_control.xacro @@ -1,11 +1,12 @@ - - + + - + mock_components/GenericSystem diff --git a/config/abb_crb15000_5_95.srdf b/config/abb_irb4600_40_255.srdf similarity index 70% rename from config/abb_crb15000_5_95.srdf rename to config/abb_irb4600_40_255.srdf index 380535d..9beefe8 100644 --- a/config/abb_crb15000_5_95.srdf +++ b/config/abb_irb4600_40_255.srdf @@ -3,7 +3,7 @@ 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 --> - + @@ -12,33 +12,26 @@ - - - - - - - - - - - - - - - - - + + + + + - + + + + + + diff --git a/config/abb_irb4600_40_255.urdf.xacro b/config/abb_irb4600_40_255.urdf.xacro new file mode 100644 index 0000000..e865037 --- /dev/null +++ b/config/abb_irb4600_40_255.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/config/initial_positions.yaml b/config/initial_positions.yaml index 0eb43b5..7997746 100644 --- a/config/initial_positions.yaml +++ b/config/initial_positions.yaml @@ -1,4 +1,4 @@ -# Default initial positions for abb_crb15000_5_95's ros2_control fake system +# Default initial positions for abb_irb4600_40_255's ros2_control fake system initial_positions: joint_1: 0 diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml index 92f9b44..1795608 100644 --- a/config/joint_limits.yaml +++ b/config/joint_limits.yaml @@ -10,31 +10,31 @@ default_acceleration_scaling_factor: 0.1 joint_limits: joint_1: has_velocity_limits: true - max_velocity: 2.1816615649929121 + max_velocity: 2.6179999999999999 has_acceleration_limits: false max_acceleration: 0 joint_2: has_velocity_limits: true - max_velocity: 2.1816615649929121 + max_velocity: 2.6179999999999999 has_acceleration_limits: false max_acceleration: 0 joint_3: has_velocity_limits: true - max_velocity: 2.4434609527920612 + max_velocity: 2.6179999999999999 has_acceleration_limits: false max_acceleration: 0 joint_4: has_velocity_limits: true - max_velocity: 3.4906585039886591 + max_velocity: 6.2831999999999999 has_acceleration_limits: false max_acceleration: 0 joint_5: has_velocity_limits: true - max_velocity: 3.4906585039886591 + max_velocity: 6.2831999999999999 has_acceleration_limits: false max_acceleration: 0 joint_6: has_velocity_limits: true - max_velocity: 3.4906585039886591 + max_velocity: 7.8540000000000001 has_acceleration_limits: false max_acceleration: 0 \ No newline at end of file diff --git a/config/kinematics.yaml b/config/kinematics.yaml index bcc4162..918382f 100644 --- a/config/kinematics.yaml +++ b/config/kinematics.yaml @@ -1,4 +1,8 @@ manipulator: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 +manipulator_lma: + kinematics_solver: lma_kinematics_plugin/LMAKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/config/moveit_controllers.yaml b/config/moveit_controllers.yaml index f37c6b5..836c3b7 100644 --- a/config/moveit_controllers.yaml +++ b/config/moveit_controllers.yaml @@ -4,9 +4,9 @@ moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControll moveit_simple_controller_manager: controller_names: - - arm_controller + - manipulator_controller - arm_controller: + manipulator_controller: type: FollowJointTrajectory action_ns: follow_joint_trajectory default: true @@ -16,6 +16,4 @@ moveit_simple_controller_manager: - joint_3 - joint_4 - joint_5 - - joint_6 - action_ns: follow_joint_trajectory - default: true \ No newline at end of file + - joint_6 \ No newline at end of file diff --git a/config/ros2_controllers.yaml b/config/ros2_controllers.yaml index 5ce31f4..5c760a5 100644 --- a/config/ros2_controllers.yaml +++ b/config/ros2_controllers.yaml @@ -3,14 +3,14 @@ controller_manager: ros__parameters: update_rate: 100 # Hz - abb_arm_controller: + manipulator_controller: type: joint_trajectory_controller/JointTrajectoryController joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster -abb_arm_controller: +manipulator_controller: ros__parameters: joints: - joint_1 diff --git a/launch/demo.launch.py b/launch/demo.launch.py index 66c7ac0..05bd408 100644 --- a/launch/demo.launch.py +++ b/launch/demo.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_demo_launch(moveit_config) diff --git a/launch/move_group.launch.py b/launch/move_group.launch.py index dde8008..e8f5298 100644 --- a/launch/move_group.launch.py +++ b/launch/move_group.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_move_group_launch(moveit_config) diff --git a/launch/moveit_rviz.launch.py b/launch/moveit_rviz.launch.py index 4c432b7..58791a7 100644 --- a/launch/moveit_rviz.launch.py +++ b/launch/moveit_rviz.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_moveit_rviz_launch(moveit_config) diff --git a/launch/rsp.launch.py b/launch/rsp.launch.py index dde7fb7..2e17fc9 100644 --- a/launch/rsp.launch.py +++ b/launch/rsp.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_rsp_launch(moveit_config) diff --git a/launch/setup_assistant.launch.py b/launch/setup_assistant.launch.py index 0dd8767..72a6e04 100644 --- a/launch/setup_assistant.launch.py +++ b/launch/setup_assistant.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_setup_assistant_launch(moveit_config) diff --git a/launch/spawn_controllers.launch.py b/launch/spawn_controllers.launch.py index 1767365..392d7fc 100644 --- a/launch/spawn_controllers.launch.py +++ b/launch/spawn_controllers.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_spawn_controllers_launch(moveit_config) diff --git a/launch/static_virtual_joint_tfs.launch.py b/launch/static_virtual_joint_tfs.launch.py index 8a2f57e..970ebf7 100644 --- a/launch/static_virtual_joint_tfs.launch.py +++ b/launch/static_virtual_joint_tfs.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/launch/warehouse_db.launch.py b/launch/warehouse_db.launch.py index f66a044..f717fe4 100644 --- a/launch/warehouse_db.launch.py +++ b/launch/warehouse_db.launch.py @@ -3,5 +3,5 @@ def generate_launch_description(): - moveit_config = MoveItConfigsBuilder("abb_crb15000_5_95", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() + moveit_config = MoveItConfigsBuilder("abb_irb4600_40_255", package_name="abb_crb15000_5_95_moveit_config").to_moveit_configs() return generate_warehouse_db_launch(moveit_config) diff --git a/package.xml b/package.xml index 9863b15..94b265c 100644 --- a/package.xml +++ b/package.xml @@ -4,9 +4,8 @@ abb_crb15000_5_95_moveit_config 0.3.0 - An automatically generated package with all the configuration and launch files for using the abb_crb15000_5_95 with the MoveIt Motion Planning Framework + An automatically generated package with all the configuration and launch files for using the abb_irb4600_40_255 with the MoveIt Motion Planning Framework - Zac Zhuo Zhang BSD @@ -15,7 +14,7 @@ https://github.com/ros-planning/moveit2/issues https://github.com/ros-planning/moveit2 - Zac Zhuo Zhang + Zhu Zhang ament_cmake @@ -31,7 +30,7 @@ We don't include them by default to prevent installing gazebo and all its dependencies. --> - abb_crb15000_support + abb_irb4600_40_255 controller_manager moveit_configs_utils moveit_ros_move_group @@ -45,6 +44,8 @@ tf2_ros warehouse_ros_mongo xacro + + ament_cmake