DreamView数据通信
WebSock通信机制
''前后端是通过WebSock进行通信,WebSock是一个双工通信。
里面有几个重要的函数
var ws = new WebSocket(“ws://echo.websocket.org”);
ws.onopen = function(){ws.send(“Test!”); };
ws.onmessage = function(evt){console.log(evt.data);ws.close();};
ws.onclose = function(evt){console.log(“WebSocketClosed!”);};
ws.onerror = function(evt){console.log(“WebSocketError!”);};
-
第一行代码是在申请一个WebSocket对象,参数是需要连接的服务器端的地址,同http协议使用http://开头一样,WebSocket协议的URL使用ws://开头,另外安全的WebSocket协议使用wss://开头。
第二行到第五行为WebSocket对象注册消息的处理函数,WebSocket对象一共支持四个消息
onopen
,onmessage
,onclose
和onerror
. -
当Browser和WebSocketServer连接成功后,会触发
onopen
消息; -
如果连接失败,发送、接收数据失败或者处理数据出现错误,browser会触发
onerror
消息; -
当Browser接收到WebSocketServer发送过来的数据时,就会触发
onmessage
消息,参数evt中包含server传输过来的数据; -
当Browser接收到WebSocketServer端发送的关闭连接请求时,就会触发
onclose
消息。我们可以看出所有的操作都是采用消息的方式触发的,这样就不会阻塞UI,使得UI有更快的响应时间,得到更好的用户体验。
frontend To backend
以start auto按钮为例进行讲解:
- 前端:当按下按钮,触发按钮事件
WS.changeDrivingMode("COMPLETE_AUTO_DRIVE");
WS为WebSock对象,进入到函数changeDrivingMode
会发现函数里面执行了websocket.send()
发送后端消息,类型为ChangeDrivingMode
changeDrivingMode(mode) {
this.websocket.send(JSON.stringify({
type: "ChangeDrivingMode",
new_mode: mode,
}));
}
-
后端:当后端收到前端的消息时会进入到后端的
onmess()
,后端的处理函数为handleData(CivetServer *server, Connection *conn, int bits, char *data,size_t data_len)
该函数会调用handleJsonData
或者handleBinaryData
在这两个函数中(handleBinaryData或handleJsonData)有一个map映射函数message_handlers_[type](json, conn);
该函数的定义为
// Message handlers keyed by message type.
std::unordered_map<std::string, MessageHandler> message_handlers_;
可以看出他根据消息类型来找出对应的处理函数,消息处理函数在函数RegisterMessageHandlers()
中注册,(该函数在hmi.cc文件里面),在函数RegisterMessageHandler()里面有许多处理句柄函数,调用 websocket对象的注册函数,进行类型和函数的一一对应关系,例如,截取其中一部分显示如下
// HMI client asks for changing driving mode.
websocket_->RegisterMessageHandler(
"ChangeDrivingMode",
[this](const Json &json, WebSocketHandler::Connection *conn) {
// json should contain {new_mode: "DrivingModeName"}.
// DrivingModeName should be one of canbus::Chassis::DrivingMode.
// For now it is either COMPLETE_MANUAL or COMPLETE_AUTO_DRIVE.
std::string new_mode;
if (JsonUtil::GetStringFromJson(json, "new_mode", &new_mode)) {
Chassis::DrivingMode mode;
if (Chassis::DrivingMode_Parse(new_mode, &mode)) {
HMIWorker::ChangeToDrivingMode(mode);
} else {
AERROR << "Unknown driving mode " << new_mode;
}
} else {
AERROR << "Truncated ChangeDrivingMode request.";
}
});
// HMI client asks for executing mode command.
websocket_->RegisterMessageHandler(
"ExecuteModeCommand",
[this](const Json &json, WebSocketHandler::Connection *conn) {
// json should contain {command: "command_name"}.
// Supported commands are: "start", "stop".
std::string command;
if (JsonUtil::GetStringFromJson(json, "command", &command)) {
HMIWorker::instance()->RunModeCommand(command);
} else {
AERROR << "Truncated mode command.";
}
});
当收到类型为ChangeDrivingMode
时,就会执行相应的函数。继续auto按钮,这里为HMIWorker::ChangeToDrivingMode(mode);
进入该函数,会发现他设置了pad topic
,然后周期发送该主题AdapterManager::PublishPad(pad)
,当别的模块接收到该主题的时候,就会去执行相应的操作,切换驾驶模式。该行为还没有找到反馈,-----> 或许前端就不再需要后端反馈了,只是让后端去执行而已。
...
control::PadMessage pad;
switch (mode) {
case Chassis::COMPLETE_MANUAL:
pad.set_action(DrivingAction::RESET);
break;
case Chassis::COMPLETE_AUTO_DRIVE:
pad.set_action(DrivingAction::START);
break;
default:
AFATAL << "Unknown action to change driving mode to "
<< Chassis::DrivingMode_Name(mode);
}
...
// Send driving action periodically until entering target driving mode.
AdapterManager::FillPadHeader("HMI", &pad);
AdapterManager::PublishPad(pad);
backend To frontend
前端会每个100ms向后端请求simulationWorld数据
modules/dreamview/frontend/src/store/websocket/websocket_realtime.js
// Request simulation world every 100ms.
clearInterval(this.timer);
this.timer = setInterval(() => {
if (this.websocket.readyState === this.websocket.OPEN) {
// Load default routing end point.
if (this.updatePOI) {
this.requestDefaultRoutingEndPoint();
this.updatePOI = false;
}
const requestPlanningData = STORE.options.showPNCMonitor;
this.websocket.send(JSON.stringify({
type: "RequestSimulationWorld",
planning: requestPlanningData,
}));
}
}, this.simWorldUpdatePeriodMs);
当后端收到请求后,会根据类型RequestSimulationWorld
找到对应的执行函数,该处理函数依旧在`
SimulationWorldUpdater::RegisterMessageHandlers()注册,只不过这次在SimulationWorldUpdater.cc
文件中。找到类型RequestSimulationWorld`对应的处理函数
websocket_->RegisterMessageHandler(
"RequestSimulationWorld",
[this](const Json &json, WebSocketHandler::Connection *conn) {
if (!sim_world_service_.ReadyToPush()) {
AWARN_EVERY(100)
<< "Not sending simulation world as the data is not ready!";
return;
}
bool enable_pnc_monitor = false;
auto planning = json.find("planning");
if (planning != json.end() && planning->is_boolean()) {
enable_pnc_monitor = json["planning"];
}
std::string to_send;
{
// Pay the price to copy the data instead of sending data over the
// wire while holding the lock.
boost::shared_lock<boost::shared_mutex> reader_lock(mutex_);
to_send = enable_pnc_monitor ? simulation_world_with_planning_data_
: simulation_world_;
}
if (FLAGS_enable_update_size_check && !enable_pnc_monitor &&
to_send.size() > FLAGS_max_update_size) {
AWARN << "update size is too big:" << to_send.size();
return;
}
websocket_->SendBinaryData(conn, to_send, true);
});
后端把simulation数据装到to_send
,然后调用SendBinaryData()
函数发送出去。
后端是怎么把simulation数据封装好呢?
Dreamview
初始化,定义好WebSock
服务器端(协议,端口号8888,以及一些地图、点云的初始化),然后start
启动,调用SimulationWorldUpdater::Start()
函数
// Time interval, in milliseconds, between pushing SimulationWorld to frontend.
static constexpr double kSimWorldTimeIntervalMs = 100;
void SimulationWorldUpdater::Start() {
// start ROS timer, one-shot = false, auto-start = true
timer_ =
AdapterManager::CreateTimer(ros::Duration(kSimWorldTimeIntervalMs / 1000),
&SimulationWorldUpdater::OnTimer, this);
}
在该函数中启动一个定时器,定时回调SimulationWorldUpdater::OnTimer
void SimulationWorldUpdater::OnTimer(const ros::TimerEvent &event) {
sim_world_service_.Update();
{
boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
sim_world_service_.GetWireFormatString(
FLAGS_sim_map_radius, &simulation_world_,//simulation_world_填值
&simulation_world_with_planning_data_);
sim_world_service_.GetRelativeMap().SerializeToString(
&relative_map_string_);
}
}
在OnTimer()
里面会执行SimulationWorldService::Update()
,该函数里面把所有的数据填充到 world_对象中,该对象的类型为SimulationWorld
,他是一个protobuf定义的类,里面是一些仿真的数据。
void SimulationWorldService::Update() {
...
world_.Clear();
AdapterManager::Observe();
UpdateWithLatestObserved("Chassis", AdapterManager::GetChassis());
UpdateWithLatestObserved("Gps", AdapterManager::GetGps());
UpdateWithLatestObserved("Localization", AdapterManager::GetLocalization());
// Clear objects received from last frame and populate with the new objects.
// TODO(siyangy, unacao): For now we are assembling the simulation_world with
// latest received perception, prediction and planning message. However, they
// may not always be perfectly aligned and belong to the same frame.
obj_map_.clear();
world_.clear_object();
UpdateWithLatestObserved("PerceptionObstacles",
AdapterManager::GetPerceptionObstacles());
UpdateWithLatestObserved("PerceptionTrafficLight",
AdapterManager::GetTrafficLightDetection(), false);
UpdateWithLatestObserved("PredictionObstacles",
AdapterManager::GetPrediction());
UpdateWithLatestObserved("Planning", AdapterManager::GetPlanning());
UpdateWithLatestObserved("ControlCommand",
AdapterManager::GetControlCommand());
UpdateWithLatestObserved("Navigation", AdapterManager::GetNavigation(),
FLAGS_use_navigation_mode);
UpdateWithLatestObserved("RelativeMap", AdapterManager::GetRelativeMap(),
FLAGS_use_navigation_mode);
for (const auto &kv : obj_map_) {
*world_.add_object() = kv.second;
}
UpdateDelays();
world_.set_sequence_num(world_.sequence_num() + 1);
world_.set_timestamp(apollo::common::time::AsInt64<millis>(Clock::Now()));
}
至此,整个DreamView通信原理分析完毕。
不足之处还请多多指正!