Skip to content

Commit

Permalink
Merge branch 'main' into sensing-imu-corrector
Browse files Browse the repository at this point in the history
  • Loading branch information
karishma1911 authored Dec 20, 2023
2 parents f923512 + bca290d commit 342f0d9
Show file tree
Hide file tree
Showing 7 changed files with 9 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,8 @@ class PlannerManager

module_ptr->publishRTCStatus();

module_ptr->publishSteeringFactor();

module_ptr->publishObjectsOfInterestMarker();

processing_time_.at(module_ptr->name()) += stop_watch_.toc(module_ptr->name(), true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
<depend>motion_utils</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand Down
2 changes: 0 additions & 2 deletions planning/behavior_velocity_traffic_light_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,6 @@

namespace behavior_velocity_planner
{
using tier4_autoware_utils::appendMarkerArray;

visualization_msgs::msg::MarkerArray TrafficLightModule::createDebugMarkerArray()
{
visualization_msgs::msg::MarkerArray debug_marker_array;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <memory>
#include <set>
#include <string>
#include <unordered_map>
#include <utility>
namespace behavior_velocity_planner
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@

#include <functional>
#include <memory>
#include <optional>

namespace behavior_velocity_planner
{
Expand Down Expand Up @@ -57,7 +58,7 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
// Debug
rclcpp::Publisher<autoware_perception_msgs::msg::TrafficSignal>::SharedPtr pub_tl_state_;

boost::optional<int> first_ref_stop_path_point_index_;
std::optional<int> first_ref_stop_path_point_index_;
};

class TrafficLightModulePlugin : public PluginWrapper<TrafficLightModuleManager>
Expand Down
7 changes: 2 additions & 5 deletions planning/behavior_velocity_traffic_light_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

#include <boost/geometry/algorithms/distance.hpp>
#include <boost/geometry/algorithms/intersection.hpp>
#include <boost/optional.hpp> // To be replaced by std::optional in C++17

#include <tf2/utils.h>

Expand All @@ -31,9 +30,7 @@

#include <algorithm>
#include <limits>
#include <map>
#include <string>
#include <utility>
#include <vector>

namespace behavior_velocity_planner
Expand All @@ -52,14 +49,14 @@ bool getBackwardPointFromBasePoint(
return true;
}

boost::optional<Point2d> findNearestCollisionPoint(
std::optional<Point2d> findNearestCollisionPoint(
const LineString2d & line1, const LineString2d & line2, const Point2d & origin)
{
std::vector<Point2d> collision_points;
bg::intersection(line1, line2, collision_points);

if (collision_points.empty()) {
return boost::none;
return std::nullopt;
}

// check nearest collision point
Expand Down
7 changes: 3 additions & 4 deletions planning/behavior_velocity_traffic_light_module/src/scene.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@

#include <memory>
#include <optional>
#include <string>
#include <tuple>
#include <vector>

Expand Down Expand Up @@ -81,7 +80,7 @@ class TrafficLightModule : public SceneModuleInterface

inline State getTrafficLightModuleState() const { return state_; }

inline boost::optional<int> getFirstRefStopPathPointIndex() const
inline std::optional<int> getFirstRefStopPathPointIndex() const
{
return first_ref_stop_path_point_index_;
}
Expand Down Expand Up @@ -130,9 +129,9 @@ class TrafficLightModule : public SceneModuleInterface
// prevent stop chattering
std::unique_ptr<Time> stop_signal_received_time_ptr_{};

boost::optional<int> first_ref_stop_path_point_index_;
std::optional<int> first_ref_stop_path_point_index_;

boost::optional<Time> traffic_signal_stamp_;
std::optional<Time> traffic_signal_stamp_;

// Traffic Light State
TrafficSignal looking_tl_state_;
Expand Down

0 comments on commit 342f0d9

Please sign in to comment.