Skip to content

Commit

Permalink
WIP: ros2-ified
Browse files Browse the repository at this point in the history
  • Loading branch information
130s committed Jun 7, 2023
1 parent b5ce355 commit eb41a1e
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 25 deletions.
13 changes: 7 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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()
40 changes: 21 additions & 19 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,28 +13,30 @@
<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/ros-planning/moveit/issues</url>
<url type="repository">https://github.com/ros-planning/moveit</url>
<buildtool_depend>ament_cmake</buildtool_depend>

<buildtool_depend>catkin</buildtool_depend>

<run_depend>moveit_ros_move_group</run_depend>
<run_depend>moveit_fake_controller_manager</run_depend>
<run_depend>moveit_kinematics</run_depend>
<run_depend>moveit_planners</run_depend>
<run_depend>moveit_ros_visualization</run_depend>
<run_depend>moveit_setup_assistant</run_depend>
<run_depend>moveit_simple_controller_manager</run_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>joint_state_publisher_gui</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rviz</run_depend>
<run_depend>tf2_ros</run_depend>
<run_depend>xacro</run_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_fake_controller_manager</exec_depend>
<exec_depend>moveit_kinematics</exec_depend>
<exec_depend>moveit_planners</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_setup_assistant</exec_depend>
<exec_depend>moveit_simple_controller_manager</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>xacro</exec_depend>
<!-- The next 2 packages are required for the gazebo simulation.
We don't include them by default to prevent installing gazebo and all its dependencies. -->
<!-- <run_depend>joint_trajectory_controller</run_depend> -->
<!-- <run_depend>gazebo_ros_control</run_depend> -->
<!-- <exec_depend>joint_trajectory_controller</exec_depend> -->
<!-- <exec_depend>gazebo_ros_control</exec_depend> -->
<!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->
<!-- <run_depend>warehouse_ros_mongo</run_depend> -->
<run_depend version_gte="0.10.0">franka_description</run_depend>
<!-- <exec_depend>warehouse_ros_mongo</exec_depend> -->
<exec_depend version_gte="0.10.0">franka_description</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>

0 comments on commit eb41a1e

Please sign in to comment.