diff --git a/CMakeLists.txt b/CMakeLists.txt index 675c9ac..883df09 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,11 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 3.8) project(panda_moveit_config) -find_package(catkin REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) -catkin_package() - -install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} PATTERN "setup_assistant.launch" EXCLUDE) -install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +ament_package() diff --git a/package.xml b/package.xml index 4ed28fd..9a948e9 100644 --- a/package.xml +++ b/package.xml @@ -13,28 +13,30 @@ http://moveit.ros.org/ https://github.com/ros-planning/moveit/issues https://github.com/ros-planning/moveit + ament_cmake - catkin - - moveit_ros_move_group - moveit_fake_controller_manager - moveit_kinematics - moveit_planners - moveit_ros_visualization - moveit_setup_assistant - moveit_simple_controller_manager - joint_state_publisher - joint_state_publisher_gui - robot_state_publisher - rviz - tf2_ros - xacro + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz + tf2_ros + xacro - - + + - - franka_description + + franka_description + + ament_cmake +