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

Arc 258 more humble #2475

Merged
merged 10 commits into from
Dec 3, 2024
Merged
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
2 changes: 1 addition & 1 deletion .github/workflows/humble-upgraded-packages.txt
Original file line number Diff line number Diff line change
@@ -1 +1 @@
approximate_intersection carma motion_prediction_visualizer system_controller object_visualizer mock_controller_driver object_detection_tracking gnss_to_map_convertor mobilitypath_visualizer bsm_generator trajectory_visualizer trajectory_executor lightbar_manager mobilitypath_publisher guidance port_drayage_plugin subsystem_controllers carma_wm roadway_objects basic_autonomy carma_guidance_plugins plan_delegator traffic_incident_parser platooning_tactical_plugin intersection_transit_maneuvering light_controlled_intersection_tactical_plugin stop_and_dwell_strategic_plugin cooperative_lanechange lci_strategic_plugin stop_controlled_intersection_tactical_plugin sci_strategic_plugin inlanecruising_plugin platooning_control trajectory_follower_wrapper approaching_emergency_vehicle_plugin yield_plugin
approximate_intersection carma motion_prediction_visualizer system_controller object_visualizer mock_controller_driver object_detection_tracking gnss_to_map_convertor mobilitypath_visualizer bsm_generator trajectory_visualizer trajectory_executor lightbar_manager mobilitypath_publisher guidance port_drayage_plugin subsystem_controllers carma_wm roadway_objects basic_autonomy carma_guidance_plugins plan_delegator traffic_incident_parser platooning_tactical_plugin intersection_transit_maneuvering light_controlled_intersection_tactical_plugin stop_and_dwell_strategic_plugin cooperative_lanechange lci_strategic_plugin stop_controlled_intersection_tactical_plugin sci_strategic_plugin inlanecruising_plugin platooning_control trajectory_follower_wrapper approaching_emergency_vehicle_plugin yield_plugin arbitrator carma_cloud_client carma_cooperative_perception carma_wm_ctrl frame_transformer pure_pursuit_wrapper stop_and_wait_plugin
5 changes: 3 additions & 2 deletions arbitrator/include/arbitrator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,9 @@
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "vehicle_state.hpp"
#include "arbitrator_state_machine.hpp"
Expand Down Expand Up @@ -64,7 +65,7 @@ namespace arbitrator
sm_(sm),
nh_(nh),
min_plan_duration_(min_plan_duration),
time_between_plans_(planning_period),
time_between_plans_(rclcpp::Duration::from_seconds(planning_period)),
capabilities_interface_(ci),
planning_strategy_(planning_strategy),
initialized_(false),
Expand Down
2 changes: 1 addition & 1 deletion arbitrator/include/capabilities_interface.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ namespace arbitrator
continue;
}

const auto response = client->async_send_request(msg);
auto response = client->async_send_request(msg);

switch (const auto status{response.wait_for(500ms)}) {
case std::future_status::ready:
Expand Down
1 change: 1 addition & 0 deletions arbitrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
<depend>carma_wm</depend>
<depend>tf</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>rapidjson</depend>

Expand Down
4 changes: 2 additions & 2 deletions arbitrator/src/arbitrator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ namespace arbitrator
auto bss = std::make_shared<arbitrator::BeamSearchStrategy>(config_.beam_width);

auto png = std::make_shared<arbitrator::PluginNeighborGenerator<arbitrator::CapabilitiesInterface>>(ci);
arbitrator::TreePlanner tp(cf, png, bss, rclcpp::Duration(config_.target_plan_duration* 1e9));
arbitrator::TreePlanner tp(cf, png, bss, rclcpp::Duration::from_nanoseconds(config_.target_plan_duration* 1e9));

wm_listener_ = std::make_shared<carma_wm::WMListener>(
this->get_node_base_interface(), this->get_node_logging_interface(),
Expand All @@ -81,7 +81,7 @@ namespace arbitrator
std::make_shared<ArbitratorStateMachine>(sm),
ci,
std::make_shared<TreePlanner>(tp),
rclcpp::Duration(config_.min_plan_duration* 1e9),
rclcpp::Duration::from_nanoseconds(config_.min_plan_duration* 1e9),
1/config_.planning_frequency,
wm_ );

Expand Down
2 changes: 1 addition & 1 deletion arbitrator/src/tree_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace arbitrator
open_list_to_evaluate.push_back(std::make_pair(root, INF));

carma_planning_msgs::msg::ManeuverPlan longest_plan = root; // Track longest plan in case target length is never reached
rclcpp::Duration longest_plan_duration = rclcpp::Duration(0);
rclcpp::Duration longest_plan_duration = rclcpp::Duration::from_nanoseconds(0);


while (!open_list_to_evaluate.empty())
Expand Down
1 change: 1 addition & 0 deletions carma_cloud_client/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
<depend>j2735_v2x_msgs</depend>
<depend>carma_v2x_msgs</depend>
<depend>j2735_convertor</depend>
<depend>std_srvs</depend>

<!-- <depend>qhttpengine</depend> -->
<!-- <depend>v2xhubWebAPI</depend> -->
Expand Down
10 changes: 2 additions & 8 deletions carma_cooperative_perception/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,6 @@ carma_check_ros_version(2)
# `dependencies.cmake`.
find_package(ament_cmake_auto REQUIRED)

# Needed so CMake can find the vendored PROJ4 module file. Th FindPROJ4.cmake
# module file can be removed if we upgrade to a more recent PROJ version. See
# https://github.com/usdot-fhwa-stol/carma-platform/issues/2139 for updates.
list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake)

include(cmake_options.cmake)
include(dependencies.cmake)

Expand All @@ -48,8 +43,7 @@ file(TOUCH ${PROJECT_BINARY_DIR}/COLCON_IGNORE)
# Configures CARMA package default settings
carma_package()

# C17 CMake support added in CMake 3.21
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_C_STANDARD 11)

# This will automatically add include files from include/carma_cooperative_perception
Expand All @@ -69,7 +63,7 @@ ament_auto_add_library(carma_cooperative_perception SHARED
)

target_link_libraries(carma_cooperative_perception
${PROJ4_LIBRARIES} # Note: Newer versions of PROJ use PROJ::proj
${PROJ_LIBRARIES}
GSL # Note: Newer versions of GSL use Microsoft.GSL::GSL
units::units
multiple_object_tracking::multiple_object_tracking
Expand Down
91 changes: 0 additions & 91 deletions carma_cooperative_perception/cmake/FindPROJ4.cmake

This file was deleted.

8 changes: 1 addition & 7 deletions carma_cooperative_perception/dependencies.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,7 @@ CPMAddPackage(NAME units

find_package(multiple_object_tracking REQUIRED)

# CARMA currently uses PROJ version 6.3.1, which is not designed to be incorporated
# as a subdirectory into larger projects. If CARMA upgrades to a newer version, we
# could use the CPMAddPackage(...) command to install PROJ as a source dependency
# if there is no version already locally available.
# See https://github.com/usdot-fhwa-stol/carma-platform/issues/2139 for the PROJ
# version upgrade plans.
find_package(PROJ4 REQUIRED MODULE)
find_package(PROJ REQUIRED MODULE)

# lint_cmake: -readability/wonkycase
CPMAddPackage(NAME Microsoft.GSL
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,8 @@ class SdsmToDetectionListNode : public carma_ros2_utils::CarmaLifecycleNode
"input/georeference", 1,
[this](std_msgs::msg::String::SharedPtr msg_ptr) { georeference_ = msg_ptr->data; })},
cdasim_clock_sub_{create_subscription<rosgraph_msgs::msg::Clock>(
"input/cdasim_clock", 1, [this](rosgraph_msgs::msg::Clock::ConstSharedPtr msg_ptr) {
cdasim_time_ = msg_ptr->clock;
})}
"input/cdasim_clock", 1,
[this](rosgraph_msgs::msg::Clock::ConstSharedPtr msg_ptr) { cdasim_time_ = msg_ptr->clock; })}
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ DetectionListVizNode::DetectionListVizNode(const rclcpp::NodeOptions & options)
[this](carma_cooperative_perception_interfaces::msg::DetectionList::ConstSharedPtr msg_ptr) {
visualization_msgs::msg::MarkerArray markers;

for (const auto detection : msg_ptr->detections) {
for (const auto & detection : msg_ptr->detections) {
visualization_msgs::msg::Marker marker;

marker.header = detection.header;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,10 +139,10 @@ auto ExternalObjectListToSdsmNode::publish_as_sdsm(const external_objects_msg_ty

auto ExternalObjectListToSdsmNode::update_georeference(const georeference_msg_type & msg) -> void
{
if (map_georeference_ != msg.data)
{
if (map_georeference_ != msg.data) {
map_georeference_ = msg.data;
map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(map_georeference_.c_str());
map_projector_ =
std::make_shared<lanelet::projection::LocalFrameProjector>(map_georeference_.c_str());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ auto HostVehicleFilterNode::handle_on_configure(

RCLCPP_ERROR(
get_logger(),
"Cannot change parameter 'distance_threshold_meters': " + result.reason);
("Cannot change parameter 'distance_threshold_meters': " + result.reason).c_str());

break;
}
Expand All @@ -86,7 +86,7 @@ auto HostVehicleFilterNode::handle_on_configure(

RCLCPP_ERROR(
get_logger(),
"Cannot change parameter 'distance_threshold_meters': " + result.reason);
("Cannot change parameter 'distance_threshold_meters': " + result.reason).c_str());

break;
} else {
Expand Down
9 changes: 5 additions & 4 deletions carma_cooperative_perception/src/msg_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,19 @@

#include "carma_cooperative_perception/msg_conversion.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <carma_cooperative_perception_interfaces/msg/track.hpp>
#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
#include <carma_perception_msgs/msg/external_object.hpp>
#include <carma_perception_msgs/msg/external_object_list.hpp>
#include <j2735_v2x_msgs/msg/d_date_time.hpp>
#include <j2735_v2x_msgs/msg/personal_device_user_type.hpp>
#include <j2735_v2x_msgs/msg/positional_accuracy.hpp>
#include <j2735_v2x_msgs/to_floating_point.hpp>
#include <j3224_v2x_msgs/msg/detected_object_data.hpp>
#include <j3224_v2x_msgs/msg/equipment_type.hpp>
#include <j3224_v2x_msgs/msg/measurement_time_offset.hpp>
#include <j3224_v2x_msgs/msg/object_type.hpp>
#include <j2735_v2x_msgs/msg/positional_accuracy.hpp>
#include <j3224_v2x_msgs/msg/equipment_type.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <algorithm>
#include <cctype>
Expand Down Expand Up @@ -577,7 +577,8 @@ auto to_sdsm_msg(
sdsm.equipment_type.equipment_type = j3224_v2x_msgs::msg::EquipmentType::OBU;
sdsm.ref_pos_xy_conf.semi_major = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_UNAVAILABLE;
sdsm.ref_pos_xy_conf.semi_minor = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_UNAVAILABLE;
sdsm.ref_pos_xy_conf.orientation = j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_ORIENTATION_UNAVAILABLE;
sdsm.ref_pos_xy_conf.orientation =
j2735_v2x_msgs::msg::PositionalAccuracy::ACCURACY_ORIENTATION_UNAVAILABLE;
sdsm.objects = detected_object_list;

return sdsm;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@

#include "carma_cooperative_perception/multiple_object_tracker_component.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <units.h>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <algorithm>
#include <chrono>
Expand Down Expand Up @@ -283,7 +283,8 @@ auto MultipleObjectTrackerNode::handle_on_configure(
result.reason = "parameter is read-only while node is in 'Active' state";

RCLCPP_ERROR(
get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
get_logger(),
("Cannot change parameter 'execution_frequency_hz': " + result.reason).c_str());

break;
} else {
Expand All @@ -295,7 +296,8 @@ auto MultipleObjectTrackerNode::handle_on_configure(
result.reason = "parameter is read-only while node is in 'Active' state";

RCLCPP_ERROR(
get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
get_logger(),
("Cannot change parameter 'execution_frequency_hz': " + result.reason).c_str());

break;
} else {
Expand All @@ -313,7 +315,8 @@ auto MultipleObjectTrackerNode::handle_on_configure(
result.reason = "parameter is read-only while node is in 'Active' state";

RCLCPP_ERROR(
get_logger(), "Cannot change parameter 'execution_frequency_hz': " + result.reason);
get_logger(),
("Cannot change parameter 'execution_frequency_hz': " + result.reason).c_str());

break;
} else {
Expand Down
3 changes: 2 additions & 1 deletion carma_wm/include/carma_wm/WorldModel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <exception>
#include <memory>
#include <tuple>
#include <optional>
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/primitives/Area.h>
#include <lanelet2_core/primitives/Lanelet.h>
Expand Down Expand Up @@ -450,4 +451,4 @@ class WorldModel
};
// Helpful using declarations for carma_wm classes
using WorldModelConstPtr = std::shared_ptr<const WorldModel>;
} // namespace carma_wm
} // namespace carma_wm
2 changes: 1 addition & 1 deletion carma_wm_ctrl/src/GeofenceSchedule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ std::pair<bool, rclcpp::Time> GeofenceSchedule::getNextInterval(const rclcpp::Ti

// Iterate over the day to find the next control interval
constexpr int num_sec_in_day = 86400;
const rclcpp::Duration full_day(num_sec_in_day* 1e9);
const rclcpp::Duration full_day = rclcpp::Duration::from_nanoseconds(num_sec_in_day* 1e9);
bool time_in_active_period = false; // Flag indicating if the requested time is within an active control span

while (cur_start < full_day && ros_time_of_day > rclcpp::Time(cur_start.nanoseconds(), clock_type))
Expand Down
Loading
Loading