Skip to content

Commit

Permalink
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
Browse files Browse the repository at this point in the history
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
  • Loading branch information
TauTheLepton authored Jan 16, 2025
2 parents 88de6b2 + 82d6085 commit 7700bf0
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ struct FieldOperatorApplication : public rclcpp::Node,

auto clearRoute() -> void;

auto setVelocityLimit(const double velocity_limit) -> void;
auto emplaceSetVelocityLimitTask(const double velocity_limit) -> void;

auto enableAutowareControl() -> void;

Expand Down Expand Up @@ -166,8 +166,6 @@ struct FieldOperatorApplication : public rclcpp::Node,
auto getTurnIndicatorsCommandName() const -> std::string;

auto requestAutoModeForCooperation(const std::string & module_name, const bool enable) -> void;

auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray;
};
} // namespace concealer

Expand Down
13 changes: 1 addition & 12 deletions external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,17 +346,6 @@ auto FieldOperatorApplication::getTurnIndicatorsCommandName() const -> std::stri
}
}

auto FieldOperatorApplication::getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray
{
traffic_simulator_msgs::msg::WaypointsArray waypoints;

for (const auto & point : getTrajectory().points) {
waypoints.waypoints.emplace_back(point.pose.position);
}

return waypoints;
}

auto FieldOperatorApplication::initialize(const geometry_msgs::msg::Pose & initial_pose) -> void
{
if (not std::exchange(initialized, true)) {
Expand Down Expand Up @@ -544,7 +533,7 @@ auto FieldOperatorApplication::sendCooperateCommand(
}
}

auto FieldOperatorApplication::setVelocityLimit(const double velocity_limit) -> void
auto FieldOperatorApplication::emplaceSetVelocityLimitTask(const double velocity_limit) -> void
{
task_queue.delay([this, velocity_limit]() {
auto request = std::make_shared<SetVelocityLimit::Request>();
Expand Down
12 changes: 10 additions & 2 deletions simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,15 @@ auto EgoEntity::getCurrentPose() const -> const geometry_msgs::msg::Pose &

auto EgoEntity::getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray
{
return FieldOperatorApplication::getWaypoints();
traffic_simulator_msgs::msg::WaypointsArray waypoints_array;
const auto trajectory = getTrajectory().points;
waypoints_array.waypoints.reserve(trajectory.size());

std::transform(
trajectory.cbegin(), trajectory.cend(), std::back_inserter(waypoints_array.waypoints),
[](const auto & point) { return point.pose.position; });

return waypoints_array;
}

void EgoEntity::updateFieldOperatorApplication()
Expand Down Expand Up @@ -274,7 +282,7 @@ auto EgoEntity::requestSpeedChange(
auto EgoEntity::setVelocityLimit(double value) -> void
{
behavior_parameter_.dynamic_constraints.max_speed = value;
FieldOperatorApplication::setVelocityLimit(value);
emplaceSetVelocityLimitTask(value);
}

auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void
Expand Down

0 comments on commit 7700bf0

Please sign in to comment.