Skip to content

Commit

Permalink
fix: apply fixes for rolling (tier4#821)
Browse files Browse the repository at this point in the history
* fix(component_interface_utils): add USE_DEPRECATED_TO_YAML

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* fix(lidar_apollo_instance_segmentation): add USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* add rclcpp_components to package.xml

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and boyali committed Oct 19, 2022
1 parent 7cadab3 commit 1c0834c
Show file tree
Hide file tree
Showing 8 changed files with 26 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,9 @@ class Service
auto wrapped = [logger, callback](
typename SpecT::Service::Request::SharedPtr request,
typename SpecT::Service::Response::SharedPtr response) {
#ifdef USE_DEPRECATED_TO_YAML
using rosidl_generator_traits::to_yaml;
#endif
RCLCPP_INFO_STREAM(logger, "service call: " << SpecT::name << "\n" << to_yaml(*request));
callback(request, response);
RCLCPP_INFO_STREAM(logger, "service exit: " << SpecT::name << "\n" << to_yaml(*response));
Expand Down
7 changes: 7 additions & 0 deletions perception/lidar_apollo_instance_segmentation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,13 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
src/debugger.cpp
)

# workaround to allow deprecated header to build on both galactic and rolling
if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0)
target_compile_definitions(lidar_apollo_instance_segmentation PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

target_link_libraries(lidar_apollo_instance_segmentation
tensorrt_apollo_cnn_lib
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,11 @@
#include <TrtNet.hpp>

#include <pcl/common/transforms.h>
#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif
#include <tf2_ros/buffer_interface.h>
#include <tf2_ros/transform_listener.h>

Expand Down
1 change: 1 addition & 0 deletions perception/lidar_apollo_instance_segmentation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,11 @@
#include <autoware_auto_perception_msgs/msg/object_classification.hpp>

#include <pcl_conversions/pcl_conversions.h>
#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

geometry_msgs::msg::Quaternion getQuaternionFromRPY(const double r, const double p, const double y)
{
Expand Down
1 change: 1 addition & 0 deletions simulator/fault_injection/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ ament_auto_add_library(fault_injection_node_component SHARED
src/fault_injection_node/fault_injection_node.cpp
)

# workaround to allow deprecated function to build on both galactic and rolling
if(${rosidl_generator_cpp_VERSION} VERSION_LESS 2.5.0)
target_compile_definitions(fault_injection_node_component PRIVATE
USE_DEPRECATED_TO_YAML
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,6 @@ namespace fault_injection
{
#ifdef USE_DEPRECATED_TO_YAML
using rosidl_generator_traits::to_yaml;
#else
using tier4_simulation_msgs::msg::to_yaml;
#endif

FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options)
Expand Down
7 changes: 7 additions & 0 deletions system/default_ad_api/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,13 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
src/interface_version.cpp
)

# workaround to allow deprecated function to build on both galactic and rolling
if(${rosidl_generator_cpp_VERSION} VERSION_LESS 2.5.0)
target_compile_definitions(${PROJECT_NAME} PRIVATE
USE_DEPRECATED_TO_YAML
)
endif()

rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::InterfaceVersionNode")

if(BUILD_TESTING)
Expand Down

0 comments on commit 1c0834c

Please sign in to comment.