diff --git a/training/orig/3.7/src/CMakeLists.txt b/training/orig/3.7/src/CMakeLists.txt new file mode 120000 index 00000000..904b44e6 --- /dev/null +++ b/training/orig/3.7/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/hydro/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/training/orig/3.7/src/lesson_moveit/CMakeLists.txt b/training/orig/3.7/src/lesson_moveit/CMakeLists.txt new file mode 100644 index 00000000..23c1f418 --- /dev/null +++ b/training/orig/3.7/src/lesson_moveit/CMakeLists.txt @@ -0,0 +1,162 @@ +cmake_minimum_required(VERSION 2.8.3) +project(lesson_moveit) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + moveit_ros_planning_interface + workcell_config +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES lesson_moveit +# CATKIN_DEPENDS moveit_ros_planning_interface workcell_config +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(lesson_moveit +# src/${PROJECT_NAME}/lesson_moveit.cpp +# ) + +## Declare a cpp executable +add_executable(lesson_moveit src/lesson_moveit.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(lesson_moveit_node lesson_moveit_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +target_link_libraries(lesson_moveit + ${catkin_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS lesson_moveit lesson_moveit_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_lesson_moveit.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/orig/3.7/src/lesson_moveit/package.xml b/training/orig/3.7/src/lesson_moveit/package.xml new file mode 100644 index 00000000..8616c798 --- /dev/null +++ b/training/orig/3.7/src/lesson_moveit/package.xml @@ -0,0 +1,57 @@ + + + lesson_moveit + 0.0.0 + The lesson_moveit package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + moveit_ros_planning_interface + workcell_config + moveit_ros_planning_interface + workcell_config + + + + + + + + + + + diff --git a/training/orig/3.7/src/lesson_moveit/src/lesson_moveit.cpp b/training/orig/3.7/src/lesson_moveit/src/lesson_moveit.cpp new file mode 100644 index 00000000..b78aa856 --- /dev/null +++ b/training/orig/3.7/src/lesson_moveit/src/lesson_moveit.cpp @@ -0,0 +1,15 @@ +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "lesson_moveit"); + moveit::planning_interface::MoveGroup group("manipulator"); + + // start a background "spinner", so our node can process ROS messages + // - this lets us know when the move is completed + ros::AsyncSpinner spinner(1); + spinner.start(); + + // INSERT MOTION COMMANDS HERE +} diff --git a/training/orig/3.7/src/workcell_config/CMakeLists.txt b/training/orig/3.7/src/workcell_config/CMakeLists.txt new file mode 100644 index 00000000..c376fadb --- /dev/null +++ b/training/orig/3.7/src/workcell_config/CMakeLists.txt @@ -0,0 +1,161 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_config) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS +abb_common +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES workcell_config +# CATKIN_DEPENDS abb_common +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(workcell_config +# src/${PROJECT_NAME}/workcell_config.cpp +# ) + +## Declare a cpp executable +# add_executable(workcell_config_node src/workcell_config_node.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(workcell_config_node workcell_config_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +# target_link_libraries(workcell_config_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS workcell_config workcell_config_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_workcell_config.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/orig/3.7/src/workcell_config/package.xml b/training/orig/3.7/src/workcell_config/package.xml new file mode 100644 index 00000000..d1caf217 --- /dev/null +++ b/training/orig/3.7/src/workcell_config/package.xml @@ -0,0 +1,54 @@ + + + workcell_config + 0.0.0 + The workcell_config package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + abb_common + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_config/urdf/table.urdf b/training/orig/3.7/src/workcell_config/urdf/table.urdf new file mode 100644 index 00000000..c14eb8b6 --- /dev/null +++ b/training/orig/3.7/src/workcell_config/urdf/table.urdf @@ -0,0 +1,7 @@ + + + + + + + diff --git a/training/orig/3.7/src/workcell_config/urdf/table.xacro b/training/orig/3.7/src/workcell_config/urdf/table.xacro new file mode 100644 index 00000000..16f75a85 --- /dev/null +++ b/training/orig/3.7/src/workcell_config/urdf/table.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_config/urdf/workcell.urdf b/training/orig/3.7/src/workcell_config/urdf/workcell.urdf new file mode 100644 index 00000000..e505d920 --- /dev/null +++ b/training/orig/3.7/src/workcell_config/urdf/workcell.urdf @@ -0,0 +1,259 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_config/urdf/workcell.xacro b/training/orig/3.7/src/workcell_config/urdf/workcell.xacro new file mode 100644 index 00000000..214bc58b --- /dev/null +++ b/training/orig/3.7/src/workcell_config/urdf/workcell.xacro @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/.setup_assistant b/training/orig/3.7/src/workcell_moveit_config/.setup_assistant new file mode 100644 index 00000000..324fc476 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/.setup_assistant @@ -0,0 +1,8 @@ +moveit_setup_assistant_config: + URDF: + package: workcell_config + relative_path: urdf/workcell.urdf + SRDF: + relative_path: config/workcell.srdf + CONFIG: + generated_timestamp: 1400181848 \ No newline at end of file diff --git a/training/orig/3.7/src/workcell_moveit_config/CMakeLists.txt b/training/orig/3.7/src/workcell_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..aac84f14 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_moveit_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/training/orig/3.7/src/workcell_moveit_config/config/controllers.yaml b/training/orig/3.7/src/workcell_moveit_config/config/controllers.yaml new file mode 100644 index 00000000..b1936a26 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/controllers.yaml @@ -0,0 +1,6 @@ +controller_list: + - name: "" + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6] + diff --git a/training/orig/3.7/src/workcell_moveit_config/config/fake_controllers.yaml b/training/orig/3.7/src/workcell_moveit_config/config/fake_controllers.yaml new file mode 100644 index 00000000..e0c78ef8 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,9 @@ +controller_list: + - name: fake_manipulator_controller + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 \ No newline at end of file diff --git a/training/orig/3.7/src/workcell_moveit_config/config/joint_limits.yaml b/training/orig/3.7/src/workcell_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..61d164fb --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/joint_limits.yaml @@ -0,0 +1,31 @@ +joint_limits: + joint_1: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_3: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_2: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_4: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_5: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_6: + has_velocity_limits: true + max_velocity: 7.854 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/training/orig/3.7/src/workcell_moveit_config/config/kinematics.yaml b/training/orig/3.7/src/workcell_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..969ba142 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +manipulator: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 \ No newline at end of file diff --git a/training/orig/3.7/src/workcell_moveit_config/config/ompl_planning.yaml b/training/orig/3.7/src/workcell_moveit_config/config/ompl_planning.yaml new file mode 100644 index 00000000..2e3d08d4 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,38 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + ESTkConfigDefault: + type: geometric::EST + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + BKPIECEkConfigDefault: + type: geometric::BKPIECE + KPIECEkConfigDefault: + type: geometric::KPIECE + RRTkConfigDefault: + type: geometric::RRT + RRTConnectkConfigDefault: + type: geometric::RRTConnect + RRTstarkConfigDefault: + type: geometric::RRTstar + TRRTkConfigDefault: + type: geometric::TRRT + PRMkConfigDefault: + type: geometric::PRM + PRMstarkConfigDefault: + type: geometric::PRMstar +manipulator: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + projection_evaluator: joints(joint_1,joint_2) + longest_valid_segment_fraction: 0.05 \ No newline at end of file diff --git a/training/orig/3.7/src/workcell_moveit_config/config/workcell.srdf b/training/orig/3.7/src/workcell_moveit_config/config/workcell.srdf new file mode 100644 index 00000000..5cb35573 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/config/workcell.srdf @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch b/training/orig/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 00000000..e584c786 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/demo.launch b/training/orig/3.7/src/workcell_moveit_config/launch/demo.launch new file mode 100644 index 00000000..bed75809 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/demo.launch @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + [/move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..b4079ea8 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/move_group.launch b/training/orig/3.7/src/workcell_moveit_config/launch/move_group.launch new file mode 100644 index 00000000..5f2678c8 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/move_group.launch @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/moveit.rviz b/training/orig/3.7/src/workcell_moveit_config/launch/moveit.rviz new file mode 100644 index 00000000..2fd20401 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/moveit.rviz @@ -0,0 +1,291 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 701 + - 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 + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Loop Animation: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: false + 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 + TextHeight: 0.08 + 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 + Planning Group: manipulator + Query Goal State: false + 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 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world_frame + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.91643 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.78536 + Y: 1.2046 + Z: -2.17236e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.154797 + Target Frame: world_frame + Value: XYOrbit (rviz) + Yaw: 0.696764 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004f3fc0200000005fb000000100044006900730070006c006100790073010000002800000352000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000003800000019b0000017400ffffff0000047c000004f300000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 58 + Y: 24 diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch b/training/orig/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 00000000..3529d542 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,44 @@ + + + + + ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6'] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch b/training/orig/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 00000000..0cb5e0a6 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..d5e425c9 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/planning_context.launch b/training/orig/3.7/src/workcell_moveit_config/launch/planning_context.launch new file mode 100644 index 00000000..e6b47efe --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/planning_context.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..2dcd2b8e --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch b/training/orig/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..f62533a1 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..787345eb --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/setup_assistant.launch b/training/orig/3.7/src/workcell_moveit_config/launch/setup_assistant.launch new file mode 100644 index 00000000..fb8009e8 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..0e8b63d3 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/warehouse.launch b/training/orig/3.7/src/workcell_moveit_config/launch/warehouse.launch new file mode 100644 index 00000000..dbbec2a2 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..d11aaeb2 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..81b95ae2 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml b/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/training/orig/3.7/src/workcell_moveit_config/package.xml b/training/orig/3.7/src/workcell_moveit_config/package.xml new file mode 100644 index 00000000..e6b02fe5 --- /dev/null +++ b/training/orig/3.7/src/workcell_moveit_config/package.xml @@ -0,0 +1,29 @@ + + + workcell_moveit_config + 0.2.0 + + An automatically generated package with all the configuration and launch files for using the workcell with the MoveIt Motion Planning Framework + + MoveIt Setup Assistant + MoveIt Setup Assistant + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit_setup_assistant/issues + https://github.com/ros-planning/moveit_setup_assistant + + moveit_ros_move_group + moveit_planners_ompl + moveit_ros_visualization + joint_state_publisher + robot_state_publisher + xacro + workcell_config + workcell_config + + + catkin + + diff --git a/training/ref/3.7/src/CMakeLists.txt b/training/ref/3.7/src/CMakeLists.txt new file mode 120000 index 00000000..904b44e6 --- /dev/null +++ b/training/ref/3.7/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/hydro/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/training/ref/3.7/src/lesson_moveit/CMakeLists.txt b/training/ref/3.7/src/lesson_moveit/CMakeLists.txt new file mode 100644 index 00000000..23c1f418 --- /dev/null +++ b/training/ref/3.7/src/lesson_moveit/CMakeLists.txt @@ -0,0 +1,162 @@ +cmake_minimum_required(VERSION 2.8.3) +project(lesson_moveit) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + moveit_ros_planning_interface + workcell_config +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES lesson_moveit +# CATKIN_DEPENDS moveit_ros_planning_interface workcell_config +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(lesson_moveit +# src/${PROJECT_NAME}/lesson_moveit.cpp +# ) + +## Declare a cpp executable +add_executable(lesson_moveit src/lesson_moveit.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(lesson_moveit_node lesson_moveit_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +target_link_libraries(lesson_moveit + ${catkin_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS lesson_moveit lesson_moveit_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_lesson_moveit.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/ref/3.7/src/lesson_moveit/package.xml b/training/ref/3.7/src/lesson_moveit/package.xml new file mode 100644 index 00000000..8616c798 --- /dev/null +++ b/training/ref/3.7/src/lesson_moveit/package.xml @@ -0,0 +1,57 @@ + + + lesson_moveit + 0.0.0 + The lesson_moveit package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + moveit_ros_planning_interface + workcell_config + moveit_ros_planning_interface + workcell_config + + + + + + + + + + + diff --git a/training/ref/3.7/src/lesson_moveit/src/lesson_moveit.cpp b/training/ref/3.7/src/lesson_moveit/src/lesson_moveit.cpp new file mode 100644 index 00000000..68899ed8 --- /dev/null +++ b/training/ref/3.7/src/lesson_moveit/src/lesson_moveit.cpp @@ -0,0 +1,40 @@ +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "lesson_moveit"); + moveit::planning_interface::MoveGroup group("manipulator"); + + // start a background "spinner", so our node can process ROS messages + // - this lets us know when the move is completed + ros::AsyncSpinner spinner(1); + spinner.start(); + + // INSERT MOTION COMMANDS HERE + + group.setNamedTarget("home"); + group.move(); + + Eigen::Affine3d approach = Eigen::Translation3d(1.0, 0, 0.6) * + Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitY()); + group.setPoseTarget(approach); + group.move(); + + Eigen::Affine3d pick = approach.translate(0.05*Eigen::Vector3d::UnitX()); + group.setPoseTarget(pick); + group.move(); + + Eigen::Affine3d retreat = pick.translate(-0.1*Eigen::Vector3d::UnitX()); + group.setPoseTarget(retreat); + group.move(); + + std::vector inspectPos; + inspectPos.push_back(-0.35); inspectPos.push_back(0.45); inspectPos.push_back(0.57); + inspectPos.push_back(-0.64); inspectPos.push_back(-1.03); inspectPos.push_back(0.29); + group.setJointValueTarget(inspectPos); + group.move(); + + group.setNamedTarget("home"); + group.move(); +} diff --git a/training/ref/3.7/src/workcell_config/CMakeLists.txt b/training/ref/3.7/src/workcell_config/CMakeLists.txt new file mode 100644 index 00000000..c376fadb --- /dev/null +++ b/training/ref/3.7/src/workcell_config/CMakeLists.txt @@ -0,0 +1,161 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_config) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS +abb_common +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES workcell_config +# CATKIN_DEPENDS abb_common +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(workcell_config +# src/${PROJECT_NAME}/workcell_config.cpp +# ) + +## Declare a cpp executable +# add_executable(workcell_config_node src/workcell_config_node.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(workcell_config_node workcell_config_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +# target_link_libraries(workcell_config_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS workcell_config workcell_config_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_workcell_config.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/ref/3.7/src/workcell_config/package.xml b/training/ref/3.7/src/workcell_config/package.xml new file mode 100644 index 00000000..d1caf217 --- /dev/null +++ b/training/ref/3.7/src/workcell_config/package.xml @@ -0,0 +1,54 @@ + + + workcell_config + 0.0.0 + The workcell_config package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + abb_common + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_config/urdf/table.urdf b/training/ref/3.7/src/workcell_config/urdf/table.urdf new file mode 100644 index 00000000..c14eb8b6 --- /dev/null +++ b/training/ref/3.7/src/workcell_config/urdf/table.urdf @@ -0,0 +1,7 @@ + + + + + + + diff --git a/training/ref/3.7/src/workcell_config/urdf/table.xacro b/training/ref/3.7/src/workcell_config/urdf/table.xacro new file mode 100644 index 00000000..16f75a85 --- /dev/null +++ b/training/ref/3.7/src/workcell_config/urdf/table.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_config/urdf/workcell.urdf b/training/ref/3.7/src/workcell_config/urdf/workcell.urdf new file mode 100644 index 00000000..e505d920 --- /dev/null +++ b/training/ref/3.7/src/workcell_config/urdf/workcell.urdf @@ -0,0 +1,259 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_config/urdf/workcell.xacro b/training/ref/3.7/src/workcell_config/urdf/workcell.xacro new file mode 100644 index 00000000..214bc58b --- /dev/null +++ b/training/ref/3.7/src/workcell_config/urdf/workcell.xacro @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/.setup_assistant b/training/ref/3.7/src/workcell_moveit_config/.setup_assistant new file mode 100644 index 00000000..324fc476 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/.setup_assistant @@ -0,0 +1,8 @@ +moveit_setup_assistant_config: + URDF: + package: workcell_config + relative_path: urdf/workcell.urdf + SRDF: + relative_path: config/workcell.srdf + CONFIG: + generated_timestamp: 1400181848 \ No newline at end of file diff --git a/training/ref/3.7/src/workcell_moveit_config/CMakeLists.txt b/training/ref/3.7/src/workcell_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..aac84f14 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_moveit_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/training/ref/3.7/src/workcell_moveit_config/config/controllers.yaml b/training/ref/3.7/src/workcell_moveit_config/config/controllers.yaml new file mode 100644 index 00000000..b1936a26 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/controllers.yaml @@ -0,0 +1,6 @@ +controller_list: + - name: "" + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6] + diff --git a/training/ref/3.7/src/workcell_moveit_config/config/fake_controllers.yaml b/training/ref/3.7/src/workcell_moveit_config/config/fake_controllers.yaml new file mode 100644 index 00000000..e0c78ef8 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,9 @@ +controller_list: + - name: fake_manipulator_controller + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 \ No newline at end of file diff --git a/training/ref/3.7/src/workcell_moveit_config/config/joint_limits.yaml b/training/ref/3.7/src/workcell_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..61d164fb --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/joint_limits.yaml @@ -0,0 +1,31 @@ +joint_limits: + joint_1: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_3: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_2: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_4: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_5: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_6: + has_velocity_limits: true + max_velocity: 7.854 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/training/ref/3.7/src/workcell_moveit_config/config/kinematics.yaml b/training/ref/3.7/src/workcell_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..969ba142 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +manipulator: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 \ No newline at end of file diff --git a/training/ref/3.7/src/workcell_moveit_config/config/ompl_planning.yaml b/training/ref/3.7/src/workcell_moveit_config/config/ompl_planning.yaml new file mode 100644 index 00000000..2e3d08d4 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,38 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + ESTkConfigDefault: + type: geometric::EST + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + BKPIECEkConfigDefault: + type: geometric::BKPIECE + KPIECEkConfigDefault: + type: geometric::KPIECE + RRTkConfigDefault: + type: geometric::RRT + RRTConnectkConfigDefault: + type: geometric::RRTConnect + RRTstarkConfigDefault: + type: geometric::RRTstar + TRRTkConfigDefault: + type: geometric::TRRT + PRMkConfigDefault: + type: geometric::PRM + PRMstarkConfigDefault: + type: geometric::PRMstar +manipulator: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + projection_evaluator: joints(joint_1,joint_2) + longest_valid_segment_fraction: 0.05 \ No newline at end of file diff --git a/training/ref/3.7/src/workcell_moveit_config/config/workcell.srdf b/training/ref/3.7/src/workcell_moveit_config/config/workcell.srdf new file mode 100644 index 00000000..5cb35573 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/config/workcell.srdf @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch b/training/ref/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 00000000..e584c786 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/demo.launch b/training/ref/3.7/src/workcell_moveit_config/launch/demo.launch new file mode 100644 index 00000000..bed75809 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/demo.launch @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + [/move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..b4079ea8 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/move_group.launch b/training/ref/3.7/src/workcell_moveit_config/launch/move_group.launch new file mode 100644 index 00000000..5f2678c8 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/move_group.launch @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/moveit.rviz b/training/ref/3.7/src/workcell_moveit_config/launch/moveit.rviz new file mode 100644 index 00000000..2fd20401 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/moveit.rviz @@ -0,0 +1,291 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 701 + - 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 + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Loop Animation: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: false + 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 + TextHeight: 0.08 + 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 + Planning Group: manipulator + Query Goal State: false + 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 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world_frame + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.91643 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.78536 + Y: 1.2046 + Z: -2.17236e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.154797 + Target Frame: world_frame + Value: XYOrbit (rviz) + Yaw: 0.696764 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004f3fc0200000005fb000000100044006900730070006c006100790073010000002800000352000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000003800000019b0000017400ffffff0000047c000004f300000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 58 + Y: 24 diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch b/training/ref/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 00000000..3529d542 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,44 @@ + + + + + ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6'] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch b/training/ref/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 00000000..0cb5e0a6 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..d5e425c9 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/planning_context.launch b/training/ref/3.7/src/workcell_moveit_config/launch/planning_context.launch new file mode 100644 index 00000000..e6b47efe --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/planning_context.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..2dcd2b8e --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch b/training/ref/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..f62533a1 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..787345eb --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/setup_assistant.launch b/training/ref/3.7/src/workcell_moveit_config/launch/setup_assistant.launch new file mode 100644 index 00000000..fb8009e8 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..0e8b63d3 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/warehouse.launch b/training/ref/3.7/src/workcell_moveit_config/launch/warehouse.launch new file mode 100644 index 00000000..dbbec2a2 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..d11aaeb2 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..81b95ae2 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml b/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/training/ref/3.7/src/workcell_moveit_config/package.xml b/training/ref/3.7/src/workcell_moveit_config/package.xml new file mode 100644 index 00000000..e6b02fe5 --- /dev/null +++ b/training/ref/3.7/src/workcell_moveit_config/package.xml @@ -0,0 +1,29 @@ + + + workcell_moveit_config + 0.2.0 + + An automatically generated package with all the configuration and launch files for using the workcell with the MoveIt Motion Planning Framework + + MoveIt Setup Assistant + MoveIt Setup Assistant + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit_setup_assistant/issues + https://github.com/ros-planning/moveit_setup_assistant + + moveit_ros_move_group + moveit_planners_ompl + moveit_ros_visualization + joint_state_publisher + robot_state_publisher + xacro + workcell_config + workcell_config + + + catkin + + diff --git a/training/work/3.7/src/CMakeLists.txt b/training/work/3.7/src/CMakeLists.txt new file mode 120000 index 00000000..904b44e6 --- /dev/null +++ b/training/work/3.7/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/hydro/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/training/work/3.7/src/lesson_moveit/CMakeLists.txt b/training/work/3.7/src/lesson_moveit/CMakeLists.txt new file mode 100644 index 00000000..23c1f418 --- /dev/null +++ b/training/work/3.7/src/lesson_moveit/CMakeLists.txt @@ -0,0 +1,162 @@ +cmake_minimum_required(VERSION 2.8.3) +project(lesson_moveit) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + moveit_ros_planning_interface + workcell_config +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES lesson_moveit +# CATKIN_DEPENDS moveit_ros_planning_interface workcell_config +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(lesson_moveit +# src/${PROJECT_NAME}/lesson_moveit.cpp +# ) + +## Declare a cpp executable +add_executable(lesson_moveit src/lesson_moveit.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(lesson_moveit_node lesson_moveit_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +target_link_libraries(lesson_moveit + ${catkin_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS lesson_moveit lesson_moveit_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_lesson_moveit.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/work/3.7/src/lesson_moveit/package.xml b/training/work/3.7/src/lesson_moveit/package.xml new file mode 100644 index 00000000..8616c798 --- /dev/null +++ b/training/work/3.7/src/lesson_moveit/package.xml @@ -0,0 +1,57 @@ + + + lesson_moveit + 0.0.0 + The lesson_moveit package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + moveit_ros_planning_interface + workcell_config + moveit_ros_planning_interface + workcell_config + + + + + + + + + + + diff --git a/training/work/3.7/src/lesson_moveit/src/lesson_moveit.cpp b/training/work/3.7/src/lesson_moveit/src/lesson_moveit.cpp new file mode 100644 index 00000000..b78aa856 --- /dev/null +++ b/training/work/3.7/src/lesson_moveit/src/lesson_moveit.cpp @@ -0,0 +1,15 @@ +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "lesson_moveit"); + moveit::planning_interface::MoveGroup group("manipulator"); + + // start a background "spinner", so our node can process ROS messages + // - this lets us know when the move is completed + ros::AsyncSpinner spinner(1); + spinner.start(); + + // INSERT MOTION COMMANDS HERE +} diff --git a/training/work/3.7/src/workcell_config/CMakeLists.txt b/training/work/3.7/src/workcell_config/CMakeLists.txt new file mode 100644 index 00000000..c376fadb --- /dev/null +++ b/training/work/3.7/src/workcell_config/CMakeLists.txt @@ -0,0 +1,161 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_config) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS +abb_common +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES workcell_config +# CATKIN_DEPENDS abb_common +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} +) + +## Declare a cpp library +# add_library(workcell_config +# src/${PROJECT_NAME}/workcell_config.cpp +# ) + +## Declare a cpp executable +# add_executable(workcell_config_node src/workcell_config_node.cpp) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +# add_dependencies(workcell_config_node workcell_config_generate_messages_cpp) + +## Specify libraries to link a library or executable target against +# target_link_libraries(workcell_config_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS workcell_config workcell_config_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_workcell_config.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/training/work/3.7/src/workcell_config/package.xml b/training/work/3.7/src/workcell_config/package.xml new file mode 100644 index 00000000..d1caf217 --- /dev/null +++ b/training/work/3.7/src/workcell_config/package.xml @@ -0,0 +1,54 @@ + + + workcell_config + 0.0.0 + The workcell_config package + + + + + ros-industrial + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + abb_common + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_config/urdf/table.urdf b/training/work/3.7/src/workcell_config/urdf/table.urdf new file mode 100644 index 00000000..c14eb8b6 --- /dev/null +++ b/training/work/3.7/src/workcell_config/urdf/table.urdf @@ -0,0 +1,7 @@ + + + + + + + diff --git a/training/work/3.7/src/workcell_config/urdf/table.xacro b/training/work/3.7/src/workcell_config/urdf/table.xacro new file mode 100644 index 00000000..16f75a85 --- /dev/null +++ b/training/work/3.7/src/workcell_config/urdf/table.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_config/urdf/workcell.urdf b/training/work/3.7/src/workcell_config/urdf/workcell.urdf new file mode 100644 index 00000000..e505d920 --- /dev/null +++ b/training/work/3.7/src/workcell_config/urdf/workcell.urdf @@ -0,0 +1,259 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_config/urdf/workcell.xacro b/training/work/3.7/src/workcell_config/urdf/workcell.xacro new file mode 100644 index 00000000..214bc58b --- /dev/null +++ b/training/work/3.7/src/workcell_config/urdf/workcell.xacro @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/.setup_assistant b/training/work/3.7/src/workcell_moveit_config/.setup_assistant new file mode 100644 index 00000000..324fc476 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/.setup_assistant @@ -0,0 +1,8 @@ +moveit_setup_assistant_config: + URDF: + package: workcell_config + relative_path: urdf/workcell.urdf + SRDF: + relative_path: config/workcell.srdf + CONFIG: + generated_timestamp: 1400181848 \ No newline at end of file diff --git a/training/work/3.7/src/workcell_moveit_config/CMakeLists.txt b/training/work/3.7/src/workcell_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..aac84f14 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 2.8.3) +project(workcell_moveit_config) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/training/work/3.7/src/workcell_moveit_config/config/controllers.yaml b/training/work/3.7/src/workcell_moveit_config/config/controllers.yaml new file mode 100644 index 00000000..b1936a26 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/controllers.yaml @@ -0,0 +1,6 @@ +controller_list: + - name: "" + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6] + diff --git a/training/work/3.7/src/workcell_moveit_config/config/fake_controllers.yaml b/training/work/3.7/src/workcell_moveit_config/config/fake_controllers.yaml new file mode 100644 index 00000000..e0c78ef8 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,9 @@ +controller_list: + - name: fake_manipulator_controller + joints: + - joint_1 + - joint_2 + - joint_3 + - joint_4 + - joint_5 + - joint_6 \ No newline at end of file diff --git a/training/work/3.7/src/workcell_moveit_config/config/joint_limits.yaml b/training/work/3.7/src/workcell_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..61d164fb --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/joint_limits.yaml @@ -0,0 +1,31 @@ +joint_limits: + joint_1: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_3: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_2: + has_velocity_limits: true + max_velocity: 2.618 + has_acceleration_limits: false + max_acceleration: 0 + joint_4: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_5: + has_velocity_limits: true + max_velocity: 6.2832 + has_acceleration_limits: false + max_acceleration: 0 + joint_6: + has_velocity_limits: true + max_velocity: 7.854 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/training/work/3.7/src/workcell_moveit_config/config/kinematics.yaml b/training/work/3.7/src/workcell_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..969ba142 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +manipulator: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 \ No newline at end of file diff --git a/training/work/3.7/src/workcell_moveit_config/config/ompl_planning.yaml b/training/work/3.7/src/workcell_moveit_config/config/ompl_planning.yaml new file mode 100644 index 00000000..2e3d08d4 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,38 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + ESTkConfigDefault: + type: geometric::EST + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + BKPIECEkConfigDefault: + type: geometric::BKPIECE + KPIECEkConfigDefault: + type: geometric::KPIECE + RRTkConfigDefault: + type: geometric::RRT + RRTConnectkConfigDefault: + type: geometric::RRTConnect + RRTstarkConfigDefault: + type: geometric::RRTstar + TRRTkConfigDefault: + type: geometric::TRRT + PRMkConfigDefault: + type: geometric::PRM + PRMstarkConfigDefault: + type: geometric::PRMstar +manipulator: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + projection_evaluator: joints(joint_1,joint_2) + longest_valid_segment_fraction: 0.05 \ No newline at end of file diff --git a/training/work/3.7/src/workcell_moveit_config/config/workcell.srdf b/training/work/3.7/src/workcell_moveit_config/config/workcell.srdf new file mode 100644 index 00000000..5cb35573 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/config/workcell.srdf @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/default_warehouse_mongo_db/mongod.lock b/training/work/3.7/src/workcell_moveit_config/default_warehouse_mongo_db/mongod.lock new file mode 100755 index 00000000..e69de29b diff --git a/training/work/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch b/training/work/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 00000000..e584c786 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/demo.launch b/training/work/3.7/src/workcell_moveit_config/launch/demo.launch new file mode 100644 index 00000000..bed75809 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/demo.launch @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + [/move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..b4079ea8 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/move_group.launch b/training/work/3.7/src/workcell_moveit_config/launch/move_group.launch new file mode 100644 index 00000000..5f2678c8 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/move_group.launch @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/moveit.rviz b/training/work/3.7/src/workcell_moveit_config/launch/moveit.rviz new file mode 100644 index 00000000..2fd20401 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/moveit.rviz @@ -0,0 +1,291 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 701 + - 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 + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Loop Animation: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: false + 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 + TextHeight: 0.08 + 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 + Planning Group: manipulator + Query Goal State: false + 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 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_base: + Alpha: 1 + Show Axes: false + Show Trail: false + table_leg_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_leg_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + table_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + world_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world_frame + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.91643 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.78536 + Y: 1.2046 + Z: -2.17236e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.154797 + Target Frame: world_frame + Value: XYOrbit (rviz) + Yaw: 0.696764 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004f3fc0200000005fb000000100044006900730070006c006100790073010000002800000352000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000003800000019b0000017400ffffff0000047c000004f300000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 58 + Y: 24 diff --git a/training/work/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch b/training/work/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 00000000..3529d542 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,44 @@ + + + + + ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6'] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch b/training/work/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 00000000..0cb5e0a6 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..d5e425c9 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/planning_context.launch b/training/work/3.7/src/workcell_moveit_config/launch/planning_context.launch new file mode 100644 index 00000000..e6b47efe --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/planning_context.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..2dcd2b8e --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch b/training/work/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..f62533a1 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..787345eb --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/setup_assistant.launch b/training/work/3.7/src/workcell_moveit_config/launch/setup_assistant.launch new file mode 100644 index 00000000..fb8009e8 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..0e8b63d3 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/warehouse.launch b/training/work/3.7/src/workcell_moveit_config/launch/warehouse.launch new file mode 100644 index 00000000..dbbec2a2 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..d11aaeb2 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..81b95ae2 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + diff --git a/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml b/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/launch/workcell_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/training/work/3.7/src/workcell_moveit_config/package.xml b/training/work/3.7/src/workcell_moveit_config/package.xml new file mode 100644 index 00000000..e6b02fe5 --- /dev/null +++ b/training/work/3.7/src/workcell_moveit_config/package.xml @@ -0,0 +1,29 @@ + + + workcell_moveit_config + 0.2.0 + + An automatically generated package with all the configuration and launch files for using the workcell with the MoveIt Motion Planning Framework + + MoveIt Setup Assistant + MoveIt Setup Assistant + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit_setup_assistant/issues + https://github.com/ros-planning/moveit_setup_assistant + + moveit_ros_move_group + moveit_planners_ompl + moveit_ros_visualization + joint_state_publisher + robot_state_publisher + xacro + workcell_config + workcell_config + + + catkin + +