diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..fbfc0bc --- /dev/null +++ b/.gitignore @@ -0,0 +1,35 @@ +# C++ +################################################################ + +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app diff --git a/fetch_gazebo/CMakeLists.txt b/fetch_gazebo/CMakeLists.txt index 3c602dd..d07c19c 100644 --- a/fetch_gazebo/CMakeLists.txt +++ b/fetch_gazebo/CMakeLists.txt @@ -1,69 +1,73 @@ cmake_minimum_required(VERSION 3.7.2) project(fetch_gazebo) -find_package(Boost REQUIRED) -find_package(gazebo REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(angles REQUIRED) +find_package(control_toolbox REQUIRED) +find_package(gazebo_dev REQUIRED) +find_package(gazebo_ros REQUIRED) +find_package(robot_controllers REQUIRED) +find_package(robot_controllers_interface REQUIRED) +find_package(rclcpp REQUIRED) -find_package(catkin - REQUIRED - angles - control_toolbox - gazebo_ros - robot_controllers - robot_controllers_interface -) - -include_directories( - include - ${catkin_INCLUDE_DIRS} - ${Boost_INCLUDE_DIR} - ${GAZEBO_INCLUDE_DIRS} -) +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +include_directories(include) link_directories( - ${GAZEBO_LIBRARY_DIRS} + ${gazebo_dev_LIBRARY_DIRS} ) -catkin_package( - CATKIN_DEPENDS - control_toolbox - gazebo_plugins - gazebo_ros - robot_controllers - robot_controllers_interface - LIBRARIES - fetch_gazebo_plugin - INCLUDE_DIRS - include +# Libraries +add_library(fetch_gazebo_plugin SHARED + src/plugin.cpp ) - -add_library(fetch_gazebo_plugin src/plugin.cpp) -target_link_libraries(fetch_gazebo_plugin - ${catkin_LIBRARIES} - ${GAZEBO_LIBRARIES} +ament_target_dependencies(fetch_gazebo_plugin + angles + control_toolbox + gazebo_ros + robot_controllers + robot_controllers_interface + rclcpp ) +## Install install( TARGETS fetch_gazebo_plugin - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin ) +ament_export_include_directories( + include +) + +ament_export_dependencies(ament_cmake) +ament_export_dependencies(rclcpp) + install( DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" + DESTINATION include/${PROJECT_NAME} ) install( PROGRAMS - scripts/prepare_simulated_robot.py - scripts/prepare_simulated_robot_pick_place.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + "scripts/prepare_simulated_robot.py" + "scripts/prepare_simulated_robot_pick_place.py" + DESTINATION bin ) install( - DIRECTORY config include launch robots worlds models - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + DIRECTORY config launch robots worlds models + DESTINATION share/${PROJECT_NAME} ) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/fetch_gazebo/COLCON_IGNORE b/fetch_gazebo/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/fetch_gazebo/package.xml b/fetch_gazebo/package.xml index 0eb13b1..63102d2 100644 --- a/fetch_gazebo/package.xml +++ b/fetch_gazebo/package.xml @@ -1,5 +1,5 @@ - - + + fetch_gazebo 0.9.2 @@ -15,29 +15,33 @@ BSD http://ros.org/wiki/fetch_gazebo - catkin + ament_cmake angles gazebo_dev control_toolbox - boost - gazebo_plugins gazebo_ros + rclcpp robot_controllers robot_controllers_interface sensor_msgs - actionlib + control_msgs depth_image_proc fetch_description gazebo + gazebo_plugins image_proc - nodelet - rgbd_launch + + trajectory_msgs xacro robot_state_publisher - topic_tools + + + + ament_cmake + diff --git a/fetch_gazebo/src/plugin.cpp b/fetch_gazebo/src/plugin.cpp index 6572b11..18a7f50 100644 --- a/fetch_gazebo/src/plugin.cpp +++ b/fetch_gazebo/src/plugin.cpp @@ -35,7 +35,7 @@ // Author: Michael Ferguson #include -#include +#include "sensor_msgs/msg/joint_state.hpp" #include #include #include @@ -123,7 +123,7 @@ void FetchGazeboPlugin::Init() controller_manager_.init(pnh); // Publish joint states only after controllers are fully ready - joint_state_pub_ = nh_.advertise("joint_states", 10); + joint_state_pub_ = nh_.advertise("joint_states", 10); ROS_INFO("Finished initializing FetchGazeboPlugin"); } @@ -153,7 +153,7 @@ void FetchGazeboPlugin::OnUpdate( return; // Publish joint_state message - sensor_msgs::JointState js; + sensor_msgs::msg::JointState js; js.header.stamp = ros::Time(currTime.Double()); for (size_t i = 0; i < joints_.size(); ++i) { diff --git a/fetch_gazebo_demo/COLCON_IGNORE b/fetch_gazebo_demo/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/fetch_simulation/COLCON_IGNORE b/fetch_simulation/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/fetchit_challenge/COLCON_IGNORE b/fetchit_challenge/COLCON_IGNORE new file mode 100644 index 0000000..e69de29