Skip to content

Commit

Permalink
fix(behavior_velocity_planner): modify build error in rolling (tier4#799
Browse files Browse the repository at this point in the history
)

* fix(behavior_velocity_planner): modify build error in rolling

Signed-off-by: wep21 <[email protected]>

* 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 b2fbdf1 commit 5d9e0a4
Show file tree
Hide file tree
Showing 16 changed files with 170 additions and 5 deletions.
108 changes: 107 additions & 1 deletion planning/behavior_velocity_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,11 +67,16 @@ target_include_directories(scene_module_lib
$<INSTALL_INTERFACE:include>
)

target_include_directories(scene_module_lib
SYSTEM PUBLIC
${PCL_INCLUDE_DIRS}
)

ament_target_dependencies(scene_module_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES})

# 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(scene_module_lib PUBLIC
target_compile_definitions(scene_module_lib PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()
Expand All @@ -93,6 +98,13 @@ ament_target_dependencies(scene_module_stop_line ${BEHAVIOR_VELOCITY_PLANNER_DEP

target_link_libraries(scene_module_stop_line scene_module_lib)

# 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(scene_module_stop_line PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# Scene Module: Crosswalk
ament_auto_add_library(scene_module_crosswalk SHARED
Expand All @@ -113,6 +125,12 @@ ament_target_dependencies(scene_module_crosswalk ${BEHAVIOR_VELOCITY_PLANNER_DEP

target_link_libraries(scene_module_crosswalk scene_module_lib)

# 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(scene_module_crosswalk PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Scene Module: Intersection
ament_auto_add_library(scene_module_intersection SHARED
Expand All @@ -133,6 +151,13 @@ ament_target_dependencies(scene_module_intersection ${BEHAVIOR_VELOCITY_PLANNER_

target_link_libraries(scene_module_intersection scene_module_lib)

# 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(scene_module_intersection PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# Scene Module: Traffic Light
ament_auto_add_library(scene_module_traffic_light SHARED
Expand All @@ -151,6 +176,13 @@ ament_target_dependencies(scene_module_traffic_light ${BEHAVIOR_VELOCITY_PLANNER

target_link_libraries(scene_module_traffic_light scene_module_lib)

# 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(scene_module_traffic_light PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# Scene Module: Blind Spot
ament_auto_add_library(scene_module_blind_spot SHARED
Expand All @@ -169,6 +201,13 @@ ament_target_dependencies(scene_module_blind_spot ${BEHAVIOR_VELOCITY_PLANNER_DE

target_link_libraries(scene_module_blind_spot scene_module_lib)

# 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(scene_module_blind_spot PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# Scene Module: Detection Area
ament_auto_add_library(scene_module_detection_area SHARED
Expand All @@ -187,6 +226,13 @@ ament_target_dependencies(scene_module_detection_area ${BEHAVIOR_VELOCITY_PLANNE

target_link_libraries(scene_module_detection_area scene_module_lib)

# 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(scene_module_detection_area PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Scene Module: No Stopping Area
ament_auto_add_library(scene_module_no_stopping_area SHARED
src/scene_module/no_stopping_area/manager.cpp
Expand All @@ -204,6 +250,13 @@ ament_target_dependencies(scene_module_no_stopping_area ${BEHAVIOR_VELOCITY_PLAN

target_link_libraries(scene_module_no_stopping_area scene_module_lib)

# 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(scene_module_no_stopping_area PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# Scene Module: Virtual Traffic Light
ament_auto_add_library(scene_module_virtual_traffic_light SHARED
Expand All @@ -222,6 +275,13 @@ ament_target_dependencies(scene_module_virtual_traffic_light ${BEHAVIOR_VELOCITY

target_link_libraries(scene_module_virtual_traffic_light scene_module_lib)

# 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(scene_module_virtual_traffic_light PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()


# SceneModule OcclusionSpot
# Util
Expand All @@ -245,6 +305,13 @@ target_include_directories(occlusion_spot_lib

ament_target_dependencies(occlusion_spot_lib ${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES})

# 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(occlusion_spot_lib PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

ament_auto_add_library(scene_module_occlusion_spot SHARED
src/scene_module/occlusion_spot/manager.cpp
src/scene_module/occlusion_spot/debug.cpp
Expand All @@ -261,6 +328,13 @@ ament_target_dependencies(scene_module_occlusion_spot ${BEHAVIOR_VELOCITY_PLANNE

target_link_libraries(scene_module_occlusion_spot scene_module_lib occlusion_spot_lib)

# 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(scene_module_occlusion_spot PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Scene Module Manager
ament_auto_add_library(scene_module_manager SHARED
src/planner_manager.cpp
Expand All @@ -276,6 +350,12 @@ ament_target_dependencies(scene_module_manager ${BEHAVIOR_VELOCITY_PLANNER_DEPEN

target_link_libraries(scene_module_manager scene_module_lib)

# 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(scene_module_manager PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Node
ament_auto_add_library(behavior_velocity_planner SHARED
Expand Down Expand Up @@ -306,6 +386,13 @@ target_link_libraries(behavior_velocity_planner

ament_export_dependencies(${BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES})

# 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(behavior_velocity_planner PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

rclcpp_components_register_node(behavior_velocity_planner
PLUGIN "behavior_velocity_planner::BehaviorVelocityPlannerNode"
EXECUTABLE behavior_velocity_planner_node
Expand All @@ -320,6 +407,13 @@ if(BUILD_TESTING)
ament_auto_add_library(utilization SHARED
src/utilization/util.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(utilization PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Gtest for utilization
ament_add_gtest(utilization-test
test/src/test_state_machine.cpp
Expand All @@ -330,6 +424,12 @@ if(BUILD_TESTING)
gtest_main
utilization
)
# 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(utilization-test PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# Gtest for occlusion spot
ament_add_gtest(occlusion_spot-test
Expand All @@ -341,6 +441,12 @@ if(BUILD_TESTING)
gtest_main
scene_module_occlusion_spot
)
# 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(occlusion_spot-test PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

endif()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,11 @@

#include <geometry_msgs/msg/point.hpp>

#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

#include <memory>
#include <string>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,12 @@
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_core/primitives/Lanelet.h>
#include <tf2/utils.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

#include <vector>

Expand All @@ -54,7 +59,7 @@ inline void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped<tf
fromMsg(msg.pose, tmp);
out.setData(tmp);
}

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
// Remove after this commit is released
// https://github.com/ros2/geometry2/commit/e9da371d81e388a589540357c050e262442f1b4a
inline geometry_msgs::msg::Point & toMsg(const tf2::Vector3 & in, geometry_msgs::msg::Point & out)
Expand Down Expand Up @@ -84,6 +89,7 @@ inline void doTransform(
tf2::Vector3 v_out = t * v_in;
toMsg(v_out, t_out);
}
#endif
} // namespace tf2

namespace behavior_velocity_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,12 @@
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/LaneletMap.h>
#include <tf2/utils.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

#include <algorithm>
#include <chrono>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,14 @@

#include <boost/optional.hpp>

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

#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <algorithm>
#include <memory>
Expand Down
5 changes: 5 additions & 0 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,12 @@

#include <lanelet2_routing/Route.h>
#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 <functional>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@
#include <utilization/marker_helper.hpp>
#include <utilization/util.hpp>

#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

#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@
#include <tier4_autoware_utils/trajectory/trajectory.hpp>
#include <utilization/util.hpp>

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

#include <algorithm>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,11 @@

#include <tier4_autoware_utils/planning/planning_marker_helper.hpp>

#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

#include <string>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,12 @@
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>

#include <lanelet2_core/utility/Optional.h>

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

#include <algorithm>
#include <limits>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@
#include <utilization/marker_helper.hpp>
#include <utilization/util.hpp>

#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

namespace behavior_velocity_planner
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@
#include <utilization/marker_helper.hpp>
#include <utilization/util.hpp>

#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

namespace behavior_velocity_planner
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,12 @@
#include <boost/optional.hpp> // To be replaced by std::optional in C++17

#include <tf2/utils.h>

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

#include <algorithm>
#include <map>
Expand Down
Loading

0 comments on commit 5d9e0a4

Please sign in to comment.