Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

upgrade: porting rolling and jazzy APIs #9

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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 }}
5 changes: 5 additions & 0 deletions ch4/service/ch4_service_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
4 changes: 4 additions & 0 deletions ch4/service/ch4_service_cpp/src/single_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,11 @@ class SingleNode : public rclcpp::Node
server_ = this->create_service<rcl_interfaces::srv::GetParameters>(
"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_);
}

Expand Down
5 changes: 3 additions & 2 deletions ch4/service/ch4_service_py/ch4_service_py/self_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
3 changes: 3 additions & 0 deletions ch6/ch6_bag_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
15 changes: 15 additions & 0 deletions ch6/ch6_bag_cpp/src/operatebag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifdef JAZZY_NEWER_BAG_API
#include <filesystem>
#endif
#include <memory>
#include <string>
#include <vector>
Expand All @@ -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<TimeT> 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"});
Expand All @@ -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;
}
Expand Down
Loading