Skip to content

Commit ae93638

Browse files
authored
Merge pull request tier4#1555 from tier4/feature/remove-trajectory-subscription
Remove Autoware trajectory subscription
2 parents 93b0b0f + d80a0ab commit ae93638

File tree

3 files changed

+6
-18
lines changed

3 files changed

+6
-18
lines changed

external/concealer/include/concealer/field_operator_application.hpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@
4040
#include <tier4_external_api_msgs/msg/emergency.hpp>
4141
#include <tier4_external_api_msgs/srv/engage.hpp>
4242
#include <tier4_external_api_msgs/srv/set_velocity_limit.hpp>
43-
#include <tier4_planning_msgs/msg/trajectory.hpp>
4443
#include <tier4_rtc_msgs/msg/cooperate_status_array.hpp>
4544
#include <tier4_rtc_msgs/srv/auto_mode_with_module.hpp>
4645
#include <tier4_rtc_msgs/srv/cooperate_commands.hpp>
@@ -78,7 +77,6 @@ struct FieldOperatorApplication : public rclcpp::Node
7877
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
7978
using RouteState = autoware_adapi_v1_msgs::msg::RouteState;
8079
#endif
81-
using Trajectory = tier4_planning_msgs::msg::Trajectory;
8280
using TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
8381

8482
using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute;
@@ -105,7 +103,6 @@ struct FieldOperatorApplication : public rclcpp::Node
105103
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
106104
Subscriber<RouteState> getRouteState;
107105
#endif
108-
Subscriber<Trajectory> getTrajectory;
109106
Subscriber<TurnIndicatorsCommand> getTurnIndicatorsCommand;
110107

111108
Service<ClearRoute> requestClearRoute;
@@ -163,8 +160,6 @@ struct FieldOperatorApplication : public rclcpp::Node
163160

164161
auto getLegacyAutowareState() const -> LegacyAutowareState;
165162

166-
auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray;
167-
168163
auto requestAutoModeForCooperation(const std::string &, bool) -> void;
169164

170165
auto sendCooperateCommand(const std::string &, const std::string &) -> void;

external/concealer/src/field_operator_application.cpp

Lines changed: 0 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,6 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid)
151151
#if __has_include(<autoware_adapi_v1_msgs/msg/route_state.hpp>)
152152
getRouteState("/api/routing/state", rclcpp::QoS(1), *this),
153153
#endif
154-
getTrajectory("/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1), *this),
155154
getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this),
156155
requestClearRoute("/api/routing/clear_route", *this),
157156
requestCooperateCommands("/api/external/set/rtc_commands", *this),
@@ -300,17 +299,6 @@ auto FieldOperatorApplication::engaged() const -> bool
300299
return task_queue.empty() and getLegacyAutowareState().value == LegacyAutowareState::driving;
301300
}
302301

303-
auto FieldOperatorApplication::getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray
304-
{
305-
traffic_simulator_msgs::msg::WaypointsArray waypoints;
306-
307-
for (const auto & point : getTrajectory().points) {
308-
waypoints.waypoints.emplace_back(point.pose.position);
309-
}
310-
311-
return waypoints;
312-
}
313-
314302
auto FieldOperatorApplication::initialize(const geometry_msgs::msg::Pose & initial_pose) -> void
315303
{
316304
if (not std::exchange(initialized, true)) {

simulation/traffic_simulator/src/entity/ego_entity.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -158,7 +158,12 @@ auto EgoEntity::getCurrentPose() const -> const geometry_msgs::msg::Pose &
158158

159159
auto EgoEntity::getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray
160160
{
161-
return FieldOperatorApplication::getWaypoints();
161+
/**
162+
* @note return empty array because this function is used for visualization
163+
* Autoware's trajectory is already visualized in RViz
164+
* there is no need to visualize it second time
165+
*/
166+
return traffic_simulator_msgs::msg::WaypointsArray{};
162167
}
163168

164169
auto EgoEntity::updateFieldOperatorApplication() -> void { spinSome(); }

0 commit comments

Comments
 (0)