Skip to content

Commit

Permalink
handle duration and tf2_geometry h to hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
MishkaMN committed Nov 21, 2024
1 parent 6e1d469 commit 285eec4
Show file tree
Hide file tree
Showing 50 changed files with 788 additions and 790 deletions.

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion arbitrator/include/arbitrator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <tf2_ros/transform_listener.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
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
2 changes: 1 addition & 1 deletion basic_autonomy/src/basic_autonomy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1283,7 +1283,7 @@ namespace basic_autonomy
autoware_point.heading.real = std::cos(yaw/2);
autoware_point.heading.imag = std::sin(yaw/2);

autoware_point.time_from_start = rclcpp::Duration(times[i] * 1e9);
autoware_point.time_from_start = rclcpp::Duration::from_nanoseconds(times[i] * 1e9);
RCLCPP_DEBUG_STREAM(rclcpp::get_logger(BASIC_AUTONOMY_LOGGER), "Setting waypoint idx: " << i <<", with planner: << " << trajectory_points[i].planner_plugin_name << ", x: " << trajectory_points[i].x <<
", y: " << trajectory_points[i].y <<
", speed: " << lag_speeds[i]* 2.23694 << "mph");
Expand Down
2 changes: 1 addition & 1 deletion carma_cooperative_perception/src/msg_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "carma_cooperative_perception/msg_conversion.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#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>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "carma_cooperative_perception/multiple_object_tracker_component.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <units.h>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
Expand Down
14 changes: 7 additions & 7 deletions carma_wm_ctrl/src/GeofenceScheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ GeofenceScheduler::GeofenceScheduler(std::shared_ptr<TimerFactory> timerFactory)
{
// Create repeating loop to clear geofence timers which are no longer needed
deletion_timer_ =
timerFactory_->buildTimer(nextId(), rclcpp::Duration(1), std::bind(&GeofenceScheduler::clearTimers, this));
timerFactory_->buildTimer(nextId(), rclcpp::Duration::from_nanoseconds(1), std::bind(&GeofenceScheduler::clearTimers, this));
clock_type_ = timerFactory_->now().get_clock_type();
}

Expand Down Expand Up @@ -68,7 +68,7 @@ void GeofenceScheduler::clearTimers()
}

void GeofenceScheduler::addGeofence(std::shared_ptr<Geofence> gf_ptr)
{
{
std::lock_guard<std::mutex> guard(mutex_);

RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"), "Attempting to add Geofence with Id: " << gf_ptr->id_);
Expand All @@ -82,7 +82,7 @@ void GeofenceScheduler::addGeofence(std::shared_ptr<Geofence> gf_ptr)

if (!interval_info.first && startTime == rclcpp::Time(0, 0, clock_type_))
{
RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm_ctrl"),
RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm_ctrl"),
"Failed to add geofence as its schedule did not contain an active or upcoming control period. GF Id: "
<< gf_ptr->id_);
return;
Expand All @@ -95,7 +95,7 @@ void GeofenceScheduler::addGeofence(std::shared_ptr<Geofence> gf_ptr)

int32_t timer_id = nextId();

rclcpp::Duration control_duration = rclcpp::Duration(std::max((startTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value
rclcpp::Duration control_duration = rclcpp::Duration::from_nanoseconds(std::max((startTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value

// Build timer to trigger when this geofence becomes active
TimerPtr timer = timerFactory_->buildTimer(
Expand All @@ -119,7 +119,7 @@ void GeofenceScheduler::startGeofenceCallback(std::shared_ptr<Geofence> gf_ptr,
// Build timer to trigger when this geofence becomes inactive
int32_t ending_timer_id = nextId();

rclcpp::Duration control_duration = rclcpp::Duration(std::max((endTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value
rclcpp::Duration control_duration = rclcpp::Duration::from_nanoseconds(std::max((endTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value

TimerPtr timer = timerFactory_->buildTimer(
ending_timer_id, control_duration,
Expand Down Expand Up @@ -157,7 +157,7 @@ void GeofenceScheduler::endGeofenceCallback(std::shared_ptr<Geofence> gf_ptr, co
// Build timer to trigger when this geofence becomes active
int32_t start_timer_id = nextId();

rclcpp::Duration control_duration = rclcpp::Duration(std::max((startTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value
rclcpp::Duration control_duration = rclcpp::Duration::from_nanoseconds(std::max((startTime - timerFactory_->now()).seconds() * 1e9, 0.0)); //guard for negative value

TimerPtr timer = timerFactory_->buildTimer(
start_timer_id, control_duration,
Expand All @@ -177,4 +177,4 @@ void GeofenceScheduler::onGeofenceInactive(std::function<void(std::shared_ptr<Ge
std::lock_guard<std::mutex> guard(mutex_);
inactive_callback_ = inactive_callback;
}
} // namespace carma_wm_ctrl
} // namespace carma_wm_ctrl
Loading

0 comments on commit 285eec4

Please sign in to comment.