diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 64eed01..d14d00d 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -14,7 +14,7 @@ jobs: strategy: matrix: os: [ubuntu-22.04] - ros_distribution: [foxy, galactic, humble, rolling] + ros_distribution: [foxy, galactic, humble, jazzy, rolling] fail-fast: false steps: - name: add more dependencies @@ -23,6 +23,6 @@ jobs: sudo apt-get install -y python3-colcon-coveragepy-result sudo apt-get install -y ros-${{ matrix.ros_distribution }}-diagnostic-updater - name: build and test - uses: ros-tooling/action-ros-ci@v0.2 + uses: ros-tooling/action-ros-ci@v0.3 with: target-ros2-distro: ${{ matrix.ros_distribution }} diff --git a/ch4/service/ch4_service_cpp/CMakeLists.txt b/ch4/service/ch4_service_cpp/CMakeLists.txt index 17cd88e..ef142d4 100644 --- a/ch4/service/ch4_service_cpp/CMakeLists.txt +++ b/ch4/service/ch4_service_cpp/CMakeLists.txt @@ -9,6 +9,11 @@ endif() find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) +set(ROS_DISTRO $ENV{ROS_DISTRO}) +if(${ROS_DISTRO} STREQUAL "rolling") + add_compile_definitions(NEW_SERVICE_TEMPLATE) +endif() + set(executable_selfservice self_exec) set(executable_selfnode self_node) diff --git a/ch4/service/ch4_service_cpp/src/single_node.cpp b/ch4/service/ch4_service_cpp/src/single_node.cpp index e6ee41d..aa3489c 100644 --- a/ch4/service/ch4_service_cpp/src/single_node.cpp +++ b/ch4/service/ch4_service_cpp/src/single_node.cpp @@ -45,7 +45,11 @@ class SingleNode : public rclcpp::Node server_ = this->create_service( "get_para", std::bind(&SingleNode::service_callback, this, std::placeholders::_1, std::placeholders::_2), + #ifdef NEW_SERVICE_TEMPLATE + rclcpp::ServicesQoS(), + #else rmw_qos_profile_services_default, + #endif cb_group_); } diff --git a/ch4/service/ch4_service_py/ch4_service_py/self_service.py b/ch4/service/ch4_service_py/ch4_service_py/self_service.py index 787368d..a102761 100644 --- a/ch4/service/ch4_service_py/ch4_service_py/self_service.py +++ b/ch4/service/ch4_service_py/ch4_service_py/self_service.py @@ -12,12 +12,13 @@ # See the License for the specific language governing permissions and # limitations under the License. +from rcl_interfaces.msg import Parameter +from rcl_interfaces.srv import GetParameters + import rclpy import rclpy.executors from rclpy.node import Node -from rcl_interfaces.msg import Parameter -from rcl_interfaces.srv import GetParameters class ServerNode(Node): diff --git a/ch6/ch6_bag_cpp/CMakeLists.txt b/ch6/ch6_bag_cpp/CMakeLists.txt index 84328ca..97caf7d 100644 --- a/ch6/ch6_bag_cpp/CMakeLists.txt +++ b/ch6/ch6_bag_cpp/CMakeLists.txt @@ -19,6 +19,9 @@ endif() if(${ROS_DISTRO} STREQUAL "foxy" OR ${ROS_DISTRO} STREQUAL "galactic") add_compile_definitions(DEPRECATED_BAG_API) endif() +if(${ROS_DISTRO} STREQUAL "rolling" OR ${ROS_DISTRO} STREQUAL "jazzy") + add_compile_definitions(JAZZY_NEWER_BAG_API) +endif() set(executable_data pubdata) set(executable_bag operatebag) diff --git a/ch6/ch6_bag_cpp/src/operatebag.cpp b/ch6/ch6_bag_cpp/src/operatebag.cpp index 04229fb..451c7e9 100644 --- a/ch6/ch6_bag_cpp/src/operatebag.cpp +++ b/ch6/ch6_bag_cpp/src/operatebag.cpp @@ -12,6 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#ifdef JAZZY_NEWER_BAG_API +#include +#endif #include #include #include @@ -31,9 +34,17 @@ int main() const auto LOGTAG = std::string("OperateBag"); using TimeT = builtin_interfaces::msg::Time; TimeT time = rclcpp::Clock().now(); + #ifdef JAZZY_NEWER_BAG_API + auto rosbag_dir = std::filesystem::path("time_box"); + #else auto rosbag_dir = rcpputils::fs::path("time_box"); + #endif rclcpp::Serialization serialization; + #ifdef JAZZY_NEWER_BAG_API + std::filesystem::remove_all(rosbag_dir); + #else rcpputils::fs::remove_all(rosbag_dir); + #endif { #ifdef FOXY_BAG_API const rosbag2_cpp::StorageOptions storage_options({rosbag_dir.string(), "sqlite3"}); @@ -54,7 +65,11 @@ int main() #else writer.open(rosbag_dir.string()); #endif + #ifndef JAZZY_NEWER_BAG_API if (rcutils_system_time_now(&write_bag_msg->time_stamp) != RCL_RET_OK) { + #else + if (rcutils_system_time_now(&write_bag_msg->recv_timestamp) != RCL_RET_OK) { + #endif RCLCPP_ERROR(rclcpp::get_logger(LOGTAG), "Get time failed."); return 1; }