From 9da6455dba1ff408035986fbddd3f62d11a2486b Mon Sep 17 00:00:00 2001 From: Aaron Xiao Date: Fri, 1 Sep 2017 16:46:14 -0700 Subject: [PATCH] HMI: Remove RoutingRequest sending function which has been moved to DreamView. (#1441) --- modules/hmi/conf/ros_bridge_adapter.pb.txt | 9 ---- modules/hmi/proto/hmi_message.proto | 2 - modules/hmi/ros_bridge/BUILD | 1 - modules/hmi/ros_bridge/ros_bridge.cc | 49 ------------------- modules/hmi/web/ros_bridge_api.py | 10 ---- .../hmi/web/templates/cards/left_panel.tpl | 6 --- 6 files changed, 77 deletions(-) diff --git a/modules/hmi/conf/ros_bridge_adapter.pb.txt b/modules/hmi/conf/ros_bridge_adapter.pb.txt index 103188d4cf..a91a7f58d2 100644 --- a/modules/hmi/conf/ros_bridge_adapter.pb.txt +++ b/modules/hmi/conf/ros_bridge_adapter.pb.txt @@ -1,8 +1,3 @@ -config { - type: LOCALIZATION - mode: RECEIVE_ONLY - message_history_limit: 1 -} config { type: CHASSIS mode: RECEIVE_ONLY @@ -17,8 +12,4 @@ config { type: PAD mode: PUBLISH_ONLY } -config { - type: ROUTING_REQUEST - mode: PUBLISH_ONLY -} is_ros: true diff --git a/modules/hmi/proto/hmi_message.proto b/modules/hmi/proto/hmi_message.proto index d71c3e49ae..5d6d5c3360 100644 --- a/modules/hmi/proto/hmi_message.proto +++ b/modules/hmi/proto/hmi_message.proto @@ -22,6 +22,4 @@ message HMICommand { optional bool reset_first = 2; } optional ChangeDrivingMode change_driving_mode = 2; - - optional bool new_routing_request = 3; } diff --git a/modules/hmi/ros_bridge/BUILD b/modules/hmi/ros_bridge/BUILD index 3e82d147b6..d78ce3ed2c 100644 --- a/modules/hmi/ros_bridge/BUILD +++ b/modules/hmi/ros_bridge/BUILD @@ -13,7 +13,6 @@ cc_binary( "//modules/common/adapters:adapter_manager", "//modules/control/common", "//modules/control/proto:control_proto", - "//modules/map/hdmap:hdmap_util", "@ros//:ros_common", ], ) diff --git a/modules/hmi/ros_bridge/ros_bridge.cc b/modules/hmi/ros_bridge/ros_bridge.cc index 93de262f94..907ec05bfe 100644 --- a/modules/hmi/ros_bridge/ros_bridge.cc +++ b/modules/hmi/ros_bridge/ros_bridge.cc @@ -25,7 +25,6 @@ #include "modules/common/util/file.h" #include "modules/control/common/control_gflags.h" #include "modules/control/proto/pad_msg.pb.h" -#include "modules/map/hdmap/hdmap_util.h" DEFINE_string(adapter_config_file, @@ -36,7 +35,6 @@ using apollo::common::adapter::AdapterManager; using apollo::common::adapter::AdapterManagerConfig; using apollo::control::DrivingAction; using apollo::canbus::Chassis; -using apollo::hdmap::HDMapUtil; namespace apollo { namespace hmi { @@ -53,13 +51,6 @@ class RosBridge { &adapter_conf)); AdapterManager::Init(adapter_conf); AdapterManager::AddHMICommandCallback(OnHMICommand); - - // Init RoutingRequest template. - CHECK(apollo::common::util::GetProtoFromASCIIFile( - apollo::hdmap::EndWayPointFile(), - routing_request_template.mutable_end())); - // Init HDMap. - CHECK(HDMapUtil::BaseMapPtr()); } private: @@ -71,10 +62,6 @@ class RosBridge { } ChangeDrivingModeTo(cmd.target_mode()); } - - if (command.new_routing_request()) { - instance()->SendRoutingRequest(); - } } static bool ChangeDrivingModeTo(const Chassis::DrivingMode target_mode) { @@ -118,43 +105,7 @@ class RosBridge { AINFO << "Sent PadMessage"; } - void SendRoutingRequest() { - // Observe position from Localization. - auto* localization = AdapterManager::GetLocalization(); - localization->Observe(); - if (localization->Empty()) { - AERROR << "No Localization message received!"; - return; - } - const auto& pos = localization->GetLatestObserved().pose().position(); - - // Look up lane info from map. - apollo::hdmap::LaneInfoConstPtr lane = nullptr; - double s, l; - - HDMapUtil::BaseMap().GetNearestLane(pos, &lane, &s, &l); - if (lane == nullptr) { - AERROR << "Cannot get nearest lane from current position."; - return; - } - - // Populate message and send. - routing::RoutingRequest routing_request = routing_request_template; - auto* start_point = routing_request.mutable_start(); - start_point->set_id(lane->id().id()); - start_point->set_s(s); - auto* pose = start_point->mutable_pose(); - pose->set_x(pos.x()); - pose->set_y(pos.y()); - pose->set_z(pos.z()); - AdapterManager::FillRoutingRequestHeader(kHMIRosBridgeName, - &routing_request); - AdapterManager::PublishRoutingRequest(routing_request); - } - private: - routing::RoutingRequest routing_request_template; - DECLARE_SINGLETON(RosBridge); }; diff --git a/modules/hmi/web/ros_bridge_api.py b/modules/hmi/web/ros_bridge_api.py index 9d4c904fa9..f2705b1311 100644 --- a/modules/hmi/web/ros_bridge_api.py +++ b/modules/hmi/web/ros_bridge_api.py @@ -27,7 +27,6 @@ class RosBridgeApi(object): """ HMI ros API: change_driving_mode [manual | auto] - new_routing_request """ ros_command_pub = None ros_command_seq_num = 0 @@ -62,15 +61,6 @@ class RosBridgeApi(object): Config.log.debug('Publishing message: %s', str(cmd_msg)) cls.ros_command_pub.publish(cmd_msg) - @classmethod - def new_routing_request(cls): - """SocketIO Api: new_routing_request()""" - Config.log.info('RosBridgeApi new_routing_request') - cmd_msg = cls.__new_command_message() - cmd_msg.new_routing_request = True - Config.log.debug('Publishing message: %s', str(cmd_msg)) - cls.ros_command_pub.publish(cmd_msg) - @classmethod def __new_command_message(cls): """Create a new HMICommand message with header filled.""" diff --git a/modules/hmi/web/templates/cards/left_panel.tpl b/modules/hmi/web/templates/cards/left_panel.tpl index fc6828f276..986a51d498 100644 --- a/modules/hmi/web/templates/cards/left_panel.tpl +++ b/modules/hmi/web/templates/cards/left_panel.tpl @@ -135,12 +135,6 @@ >Start Auto -
- - -
-- GitLab