提交 f4838009 编写于 作者: U unacao 提交者: Jiangtao Hu

display point cloud in dreamview

上级 b432bb79
......@@ -84,6 +84,8 @@ Status Dreamview::Init() {
<< "CompressedImageAdapter is not initialized.";
CHECK(AdapterManager::GetImageShort())
<< "ImageShortAdapter is not initialized.";
CHECK(AdapterManager::GetPointCloud())
<< "PointCloudAdapter is not initialized.";
// Initialize and run the web server which serves the dreamview htmls and
// javascripts and handles websocket requests.
......@@ -101,7 +103,6 @@ Status Dreamview::Init() {
image_.reset(new ImageHandler());
websocket_.reset(new WebSocketHandler());
<<<<<<< HEAD
map_ws_.reset(new WebSocketHandler());
point_cloud_ws_.reset(new WebSocketHandler());
map_service_.reset(new MapService());
......
......@@ -18,6 +18,7 @@ cc_library(
"//modules/common/adapters:adapter_manager",
"//modules/dreamview/backend/common:dreamview_gflags",
"//modules/dreamview/backend/handlers:websocket",
"//modules/dreamview/proto:point_cloud_proto",
"//third_party/json",
"@com_google_protobuf//:protobuf",
"@pcl//:pcl",
......
......@@ -18,6 +18,7 @@
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/log.h"
#include "modules/common/time/time.h"
#include "modules/dreamview/backend/common/dreamview_gflags.h"
#include "pcl_conversions/pcl_conversions.h"
#include "pcl/point_cloud.h"
......@@ -28,26 +29,61 @@ namespace apollo {
namespace dreamview {
using apollo::common::adapter::AdapterManager;
using apollo::common::time::Clock;
using sensor_msgs::PointCloud2;
using Json = nlohmann::json;
constexpr int PointCloudUpdater::kDownsampleRate;
PointCloudUpdater::PointCloudUpdater(WebSocketHandler *websocket)
: websocket_(websocket) {
RegisterMessageHandlers();
}
void PointCloudUpdater::RegisterMessageHandlers() {
// Send current point_cloud status to the new client.
websocket_->RegisterConnectionReadyHandler(
[this](WebSocketHandler::Connection *conn) {
Json response;
response["type"] = "PointCloudStatus";
response["enabled"] = enabled_;
websocket_->SendData(conn, response.dump());
});
websocket_->RegisterMessageHandler(
"RequestPointCloud",
[this](const Json &json, WebSocketHandler::Connection *conn) {
std::string to_send;
// If there is no point_cloud data for more than 2 seconds, reset.
if ((point_cloud_.num_size() > 0) &&
(Clock::NowInSeconds() - last_receive_time_ > 2.0)) {
point_cloud_.clear_num();
boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
point_cloud_.SerializeToString(&point_cloud_str_);
}
{
// Pay the price to copy the data instead of sending data over the
// wire while holding the lock.
boost::shared_lock<boost::shared_mutex> lock(mutex_);
boost::shared_lock<boost::shared_mutex> reader_lock(mutex_);
to_send = point_cloud_str_;
}
websocket_->SendData(conn, to_send, true);
websocket_->SendBinaryData(conn, to_send, true);;
});
websocket_->RegisterMessageHandler(
"TogglePointCloud",
[this](const Json &json, WebSocketHandler::Connection *conn) {
auto enable = json.find("enable");
if (enable != json.end() && enable->is_boolean()) {
if (*enable) {
enabled_ = true;
} else {
enabled_ = false;
}
if (websocket_) {
Json response;
response["type"] = "PointCloudStatus";
response["enabled"] = enabled_;
// Sync the point_cloud status across all the clients.
websocket_->BroadcastData(response.dump());
}
}
});
}
......@@ -57,42 +93,30 @@ void PointCloudUpdater::Start() {
}
void PointCloudUpdater::UpdatePointCloud(const PointCloud2 &point_cloud) {
// transform from ros to pcl
pcl::PointCloud < pcl::PointXYZ > pcl_data;
pcl::fromROSMsg(point_cloud, pcl_data);
if (pcl_data.size() == 0) {
point_cloud_str_ = "[]";
if (!enabled_) {
return;
}
std::stringstream stream;
std::string data("[");
for (size_t idx = 0; idx < pcl_data.size(); idx += 2) {
last_receive_time_ = Clock::NowInSeconds();
// transform from ros to pcl
pcl::PointCloud<pcl::PointXYZ> pcl_data;
pcl::fromROSMsg(point_cloud, pcl_data);
point_cloud_.Clear();
for (size_t idx = 0; idx < pcl_data.size(); idx += kDownsampleRate) {
pcl::PointXYZ& pt = pcl_data.points[idx];
if (!isnan(pt.x) && !isnan(pt.y) && !isnan(pt.z)) {
data.append("[");
stream.str(std::string());
stream << std::fixed << std::setprecision(4) << pt.x;
data.append(stream.str());
data.append(",");
stream.str(std::string());
stream << std::fixed << std::setprecision(4) << pt.y;
data.append(stream.str());
data.append(",");
stream.str(std::string());
stream << std::fixed << std::setprecision(4) << pt.z;
data.append(stream.str());
data.append("]");
if ((idx + 1) == pcl_data.size()) {
data.append("]");
} else {
data.append(",");
}
point_cloud_.add_num(pt.x);
point_cloud_.add_num(pt.y);
// TODO(unacao): velodyne height should be updated by hmi store
// upon vehicle change.
point_cloud_.add_num(pt.z + 1.91);
}
}
boost::shared_lock<boost::shared_mutex> lock(mutex_);
point_cloud_str_ = data;
{
boost::unique_lock<boost::shared_mutex> writer_lock(mutex_);
point_cloud_.SerializeToString(&point_cloud_str_);
}
}
} // namespace dreamview
......
......@@ -29,6 +29,7 @@
#include "modules/common/log.h"
#include "modules/common/util/string_util.h"
#include "modules/dreamview/backend/handlers/websocket.h"
#include "modules/dreamview/proto/point_cloud.pb.h"
#include "sensor_msgs/PointCloud2.h"
/**
......@@ -58,18 +59,25 @@ class PointCloudUpdater {
void Start();
private:
static constexpr int kDownsampleRate = 12;
void RegisterMessageHandlers();
void UpdatePointCloud(const sensor_msgs::PointCloud2 &point_cloud);
WebSocketHandler *websocket_;
bool enabled_ = false;
// The PointCloud to be pushed to frontend.
std::string point_cloud_str_;
PointCloud point_cloud_;
// Mutex to protect concurrent access to point_cloud_str_.
// NOTE: Use boost until we have std version of rwlock support.
boost::shared_mutex mutex_;
double last_receive_time_ = 0.0;
};
} // namespace dreamview
......
......@@ -38,3 +38,6 @@ node_modules/protobufjs/bin/pbjs -t json $MAP_PROTOS \
../../common/proto/header.proto \
../../common/proto/error_code.proto \
-o proto_bundle/map_proto_bundle.json
node_modules/protobufjs/bin/pbjs -t json ../proto/point_cloud.proto \
-o proto_bundle/point_cloud_proto_bundle.json
......@@ -4,6 +4,124 @@
"nested": {
"hdmap": {
"nested": {
"Projection": {
"fields": {
"proj": {
"type": "string",
"id": 1
}
}
},
"Header": {
"fields": {
"version": {
"type": "bytes",
"id": 1
},
"date": {
"type": "bytes",
"id": 2
},
"projection": {
"type": "Projection",
"id": 3
},
"district": {
"type": "bytes",
"id": 4
},
"generation": {
"type": "bytes",
"id": 5
},
"revMajor": {
"type": "bytes",
"id": 6
},
"revMinor": {
"type": "bytes",
"id": 7
},
"left": {
"type": "double",
"id": 8
},
"top": {
"type": "double",
"id": 9
},
"right": {
"type": "double",
"id": 10
},
"bottom": {
"type": "double",
"id": 11
},
"vendor": {
"type": "bytes",
"id": 12
}
}
},
"Map": {
"fields": {
"header": {
"type": "Header",
"id": 1
},
"crosswalk": {
"rule": "repeated",
"type": "Crosswalk",
"id": 2
},
"junction": {
"rule": "repeated",
"type": "Junction",
"id": 3
},
"lane": {
"rule": "repeated",
"type": "Lane",
"id": 4
},
"stopSign": {
"rule": "repeated",
"type": "StopSign",
"id": 5
},
"signal": {
"rule": "repeated",
"type": "Signal",
"id": 6
},
"yield": {
"rule": "repeated",
"type": "YieldSign",
"id": 7
},
"overlap": {
"rule": "repeated",
"type": "Overlap",
"id": 8
},
"clearArea": {
"rule": "repeated",
"type": "ClearArea",
"id": 9
},
"speedBump": {
"rule": "repeated",
"type": "SpeedBump",
"id": 10
},
"road": {
"rule": "repeated",
"type": "Road",
"id": 11
}
}
},
"ClearArea": {
"fields": {
"id": {
......@@ -308,18 +426,6 @@
}
}
},
"MapMsg": {
"fields": {
"header": {
"type": "apollo.common.Header",
"id": 1
},
"map": {
"type": "apollo.hdmap.Map",
"id": 3
}
}
},
"LaneOverlapInfo": {
"fields": {
"startS": {
......@@ -432,124 +538,6 @@
}
}
},
"Projection": {
"fields": {
"proj": {
"type": "string",
"id": 1
}
}
},
"Header": {
"fields": {
"version": {
"type": "bytes",
"id": 1
},
"date": {
"type": "bytes",
"id": 2
},
"projection": {
"type": "Projection",
"id": 3
},
"district": {
"type": "bytes",
"id": 4
},
"generation": {
"type": "bytes",
"id": 5
},
"revMajor": {
"type": "bytes",
"id": 6
},
"revMinor": {
"type": "bytes",
"id": 7
},
"left": {
"type": "double",
"id": 8
},
"top": {
"type": "double",
"id": 9
},
"right": {
"type": "double",
"id": 10
},
"bottom": {
"type": "double",
"id": 11
},
"vendor": {
"type": "bytes",
"id": 12
}
}
},
"Map": {
"fields": {
"header": {
"type": "Header",
"id": 1
},
"crosswalk": {
"rule": "repeated",
"type": "Crosswalk",
"id": 2
},
"junction": {
"rule": "repeated",
"type": "Junction",
"id": 3
},
"lane": {
"rule": "repeated",
"type": "Lane",
"id": 4
},
"stopSign": {
"rule": "repeated",
"type": "StopSign",
"id": 5
},
"signal": {
"rule": "repeated",
"type": "Signal",
"id": 6
},
"yield": {
"rule": "repeated",
"type": "YieldSign",
"id": 7
},
"overlap": {
"rule": "repeated",
"type": "Overlap",
"id": 8
},
"clearArea": {
"rule": "repeated",
"type": "ClearArea",
"id": 9
},
"speedBump": {
"rule": "repeated",
"type": "SpeedBump",
"id": 10
},
"road": {
"rule": "repeated",
"type": "Road",
"id": 11
}
}
},
"BoundaryEdge": {
"fields": {
"curve": {
......
{
"nested": {
"apollo": {
"nested": {
"dreamview": {
"nested": {
"PointCloud": {
"fields": {
"num": {
"rule": "repeated",
"type": "float",
"id": 1,
"options": {
"packed": false
}
}
}
}
}
}
}
}
}
}
\ No newline at end of file
......@@ -2466,83 +2466,12 @@
}
}
},
"CloudReferenceLinePoint": {
"fields": {
"x": {
"type": "double",
"id": 1
},
"y": {
"type": "double",
"id": 2
},
"z": {
"type": "double",
"id": 3
},
"theta": {
"type": "double",
"id": 4
},
"kappa": {
"type": "double",
"id": 5
},
"laneS": {
"type": "double",
"id": 6
},
"dkappa": {
"type": "double",
"id": 7
}
}
},
"CloudReferenceLineSegment": {
"fields": {
"laneId": {
"type": "string",
"id": 1
},
"point": {
"rule": "repeated",
"type": "CloudReferenceLinePoint",
"id": 2
}
}
},
"CloudReferenceLineResponse": {
"fields": {
"segment": {
"rule": "repeated",
"type": "CloudReferenceLineSegment",
"id": 1
}
}
},
"NavigationPath": {
"fields": {
"pathPoint": {
"rule": "repeated",
"type": "apollo.common.PathPoint",
"id": 1
},
"pathPriority": {
"type": "uint32",
"id": 2
}
}
},
"NavigationInfo": {
"fields": {
"header": {
"type": "apollo.common.Header",
"type": "apollo.common.Path",
"id": 1
},
"navigationPath": {
"rule": "repeated",
"type": "NavigationPath",
"id": 2
}
}
}
......
......@@ -7,7 +7,7 @@ import MainView from "components/Layouts/MainView";
import ToolView from "components/Layouts/ToolView";
import PNCMonitor from "components/PNCMonitor";
import SideBar from "components/SideBar";
import WS, {MAP_WS} from "store/websocket";
import WS, {MAP_WS, POINT_CLOUD_WS} from "store/websocket";
@inject("store") @observer
......@@ -32,6 +32,7 @@ export default class Dreamview extends React.Component {
componentDidMount() {
WS.initialize();
MAP_WS.initialize();
POINT_CLOUD_WS.initialize();
window.addEventListener("resize", () => {
this.props.store.updateDimension();
});
......
......@@ -12,6 +12,8 @@ import decisionIcon from "assets/images/menu/Decision.png";
import planningIcon from "assets/images/menu/Planning.png";
import cameraIcon from "assets/images/menu/PointOfView.png";
import { POINT_CLOUD_WS } from "store/websocket";
const MenuIconMapping = {
perception: perceptionIcon,
prediction: predictionIcon,
......@@ -22,6 +24,7 @@ const MenuIconMapping = {
};
const MenuIdOptionMapping = {
perceptionPointCloud: 'showPointCloud',
perceptionVehicle: 'showObstaclesVehicle',
perceptionPedestrian: 'showObstaclesPedestrian',
perceptionBicycle: 'showObstaclesBicycle',
......@@ -54,6 +57,9 @@ class MenuItemCheckbox extends React.Component {
<ul>
<li id={id} onClick={() => {
options.toggle(MenuIdOptionMapping[id]);
if (id === "perceptionPointCloud") {
POINT_CLOUD_WS.togglePointCloud(options.showPointCloud);
}
}}>
<div className="switch">
<input type="checkbox" name={id} className="toggle-switch"
......
......@@ -15,6 +15,7 @@ import Prediction from "renderer/prediction.js";
import Routing from "renderer/routing.js";
import RoutingEditor from "renderer/routing_editor.js";
import Gnss from "renderer/gnss.js";
import PointCloud from "renderer/point_cloud.js";
const _ = require('lodash');
......@@ -70,6 +71,8 @@ class Renderer {
// The GNSS/GPS
this.gnss = new Gnss();
this.pointCloud = new PointCloud();
// The Performance Monitor
this.stats = null;
if (PARAMETERS.debug.performanceMonitor) {
......@@ -310,6 +313,11 @@ class Renderer {
this.scene.add(this.ground.mesh);
}
if (this.pointCloud.initialized === false) {
this.pointCloud.initialize();
this.scene.add(this.pointCloud.points);
}
this.adjustCamera(this.adc.mesh, this.options.cameraAngle);
this.renderer.render(this.scene, this.camera);
}
......@@ -357,6 +365,13 @@ class Renderer {
this.map.appendMapData(newData, this.coordinates, this.scene);
}
updatePointCloud(pointCloud) {
if (!this.coordinates.isInitialized() || !this.adc.mesh) {
return;
}
this.pointCloud.update(pointCloud, this.adc.mesh);
}
updateMapIndex(hash, elementIds, radius) {
if (!this.routingEditor.isInEditingMode() ||
this.routingEditor.EDITING_MAP_RADIUS === radius) {
......
import * as THREE from "three";
const MAX_POINTS = 8400;
const HEIGHT_COLOR_MAPPING = {
0.5: 0xFF0000,
1.0: 0xFF7F00,
1.5: 0xFFFF00,
2.0: 0x00FF00,
2.5: 0x0000FF,
3.0: 0x4B0082,
10.0: 0x9400D3,
};
export default class PointCloud {
constructor() {
this.points = null;
this.initialized = false;
}
initialize() {
this.points = this.createPointCloud(HEIGHT_COLOR_MAPPING[0.5]);
this.initialized = true;
}
createPointCloud(hex_color) {
const geometry = new THREE.Geometry();
const colors = [];
for (let i = 0; i < MAX_POINTS; ++i) {
const vertex = new THREE.Vector3();
vertex.set(0, 0, -10);
geometry.vertices.push(vertex);
colors[i] = new THREE.Color(hex_color);
}
geometry.colors = colors;
const material = new THREE.PointsMaterial({
size: 0.1,
transparent: true,
opacity: 0.7,
vertexColors: THREE.VertexColors
});
const points = new THREE.Points(geometry, material);
points.frustumCulled = false;
return points;
}
update(pointCloud, adcMesh) {
if (this.points === null) {
return;
}
if (pointCloud.num.length % 3 !== 0) {
console.warn('PointCloud length should be multiples of 3!');
return;
}
const pointCloudSize = pointCloud.num.length / 3;
const total = (pointCloudSize < MAX_POINTS) ? pointCloudSize : MAX_POINTS;
let color_key = 0.5;
for (let i = 0; i < total; i++) {
const x = pointCloud.num[i*3];
const y = pointCloud.num[i*3 + 1];
const z = pointCloud.num[i*3 + 2];
this.points.geometry.vertices[i].set(x, y, z + 0.8);
// Update color based on height.
if (z < 0.5) {
color_key = 0.5;
} else if (z < 1.0) {
color_key = 1.0;
} else if (z < 1.5) {
color_key = 1.5;
} else if (z < 2.0) {
color_key = 2.0;
} else if (z < 2.5) {
color_key = 2.5;
} else if (z < 3.0) {
color_key = 3.0;
} else {
color_key = 10.0;
}
this.points.geometry.colors[i].setHex(HEIGHT_COLOR_MAPPING[color_key]);
}
// Hide unused points.
for (let i = total; i < MAX_POINTS; ++i) {
this.points.geometry.vertices[i].set(0, 0, -10);
}
this.points.geometry.verticesNeedUpdate = true;
this.points.geometry.colorsNeedUpdate = true;
this.points.position.set(adcMesh.position.x, adcMesh.position.y, adcMesh.position.z);
this.points.rotation.set(0, 0, adcMesh.rotation.y);
}
}
......@@ -15,6 +15,7 @@ export default [
title: 'Perception',
type: 'checkbox',
data: {
perceptionPointCloud: 'Point Cloud',
perceptionVehicle: 'Vehicle',
perceptionPedestrian: 'Pedestrian',
perceptionBicycle: 'Bicycle',
......
......@@ -71,6 +71,7 @@ options:
showObstaclesVelocity: true
showObstaclesHeading: true
showObstaclesId: true
showPointCloud: true
showPositionGps: false
showPositionLocalization: true
cameraAngle: Default
......
......@@ -45,6 +45,7 @@ export default class Options {
PARAMETERS.options.defaults.showObstaclesHeading;
@observable showObstaclesId =
PARAMETERS.options.defaults.showObstaclesId;
@observable showPointCloud = PARAMETERS.options.defaults.showPointCloud;
@observable showPositionGps = PARAMETERS.options.defaults.showPositionGps;
@observable showPositionLocalization = PARAMETERS.options.defaults.showPositionLocalization;
......
......@@ -3,6 +3,7 @@ import PARAMETERS from "store/config/parameters.yml";
import OfflinePlaybackWebSocketEndpoint from "store/websocket/websocket_offline";
import RealtimeWebSocketEndpoint from "store/websocket/websocket_realtime";
import MapDataWebSocketEndpoint from "store/websocket/websocket_map";
import PointCloudWebSocketEndpoint from "store/websocket/websocket_point_cloud";
// Returns the websocket server address based on the web server address.
// Follows the convention that the websocket is served on the same host/port
......@@ -18,6 +19,9 @@ function deduceWebsocketServerAddr(type) {
case "map":
path = "map";
break;
case "point_cloud":
path = "pointcloud";
break;
case "sim_world":
path = OFFLINE_PLAYBACK ? "RosPlayBack" : "websocket";
break;
......@@ -36,3 +40,6 @@ export default WS;
const mapServerAddr = deduceWebsocketServerAddr("map");
export const MAP_WS = new MapDataWebSocketEndpoint(mapServerAddr);
const pointCloudServerAddr = deduceWebsocketServerAddr("point_cloud");
export const POINT_CLOUD_WS = new PointCloudWebSocketEndpoint(pointCloudServerAddr);
import STORE from "store";
import RENDERER from "renderer";
const Worker = require('worker-loader!utils/webworker.js');
export default class PointCloudWebSocketEndpoint {
constructor(serverAddr) {
this.serverAddr = serverAddr;
this.websocket = null;
this.worker = new Worker();
}
initialize() {
try {
this.websocket = new WebSocket(this.serverAddr);
this.websocket.binaryType = "arraybuffer";
} catch (error) {
console.error("Failed to establish a connection: " + error);
setTimeout(() => {
this.initialize();
}, 1000);
return;
}
this.websocket.onmessage = event => {
this.worker.postMessage({
source: 'point_cloud',
data: event.data,
});
};
this.websocket.onclose = event => {
console.log("WebSocket connection closed with code: " + event.code);
this.initialize();
};
this.worker.onmessage = event => {
if (event.data.type === "PointCloudStatus") {
STORE.setOptionStatus('showPointCloud', event.data.enabled);
} else if (STORE.options.showPointCloud === true && event.data.num !== undefined) {
RENDERER.updatePointCloud(event.data);
}
};
// Request point cloud every 100ms.
clearInterval(this.timer);
this.timer = setInterval(() => {
if (this.websocket.readyState === this.websocket.OPEN) {
if (STORE.options.showPointCloud === true) {
this.websocket.send(JSON.stringify({
type : "RequestPointCloud"
}));
} else {
RENDERER.updatePointCloud({num:[]});
}
}
}, 100);
}
togglePointCloud(enable) {
this.websocket.send(JSON.stringify({
type: "TogglePointCloud",
enable: enable,
}));
}
}
\ No newline at end of file
const protobuf = require("protobufjs/light");
const simWorldRoot = protobuf.Root.fromJSON(
require("../../proto_bundle/sim_world_proto_bundle.json")
require("../../proto_bundle/sim_world_proto_bundle.json")
);
const SimWorldMessage = simWorldRoot.lookupType("apollo.dreamview.SimulationWorld");
const mapRoot = protobuf.Root.fromJSON(require("../../proto_bundle/map_proto_bundle.json"));
const mapMessage = mapRoot.lookupType("apollo.hdmap.Map");
const pointCloudRoot = protobuf.Root.fromJSON(
require("../../proto_bundle/point_cloud_proto_bundle.json")
);
const pointCloudMessage = pointCloudRoot.lookupType("apollo.dreamview.PointCloud");
self.addEventListener("message", event => {
let message = null;
......@@ -26,9 +30,17 @@ self.addEventListener("message", event => {
{enums: String});
message.type = "MapData";
break;
case "point_cloud":
if (typeof data === "string") {
message = JSON.parse(data);
} else {
message = pointCloudMessage.toObject(
pointCloudMessage.decode(new Uint8Array(data)), {arrays: true});
}
break;
}
if (message) {
self.postMessage(message);
self.postMessage(message);
}
});
......@@ -16,6 +16,18 @@ proto_library(
],
)
cc_proto_library(
name = "point_cloud_proto",
deps = [
":point_cloud_proto_lib",
],
)
proto_library(
name = "point_cloud_proto_lib",
srcs = ["point_cloud.proto"],
)
cc_proto_library(
name = "hmi_config_proto",
deps = [
......
syntax = "proto2";
package apollo.dreamview;
message PointCloud {
repeated float num = 1;
}
......@@ -115,17 +115,6 @@ autorestart=unexpected
redirect_stderr=true
stdout_logfile=/apollo/data/log/dreamview.out
[program:sim_control]
command=/apollo/bazel-bin/modules/dreamview/dreamview --flagfile=/apollo/modules/dreamview/conf/dreamview.conf --enable_sim_control --log_dir=/apollo/data/log
autostart=false
numprocs=1
exitcodes=0
stopsignal=SIGINT
startretries=10
autorestart=unexpected
redirect_stderr=true
stdout_logfile=/apollo/data/log/dreamview.out
[program:monitor]
command=/apollo/bazel-bin/modules/monitor/monitor --flagfile=/apollo/modules/monitor/conf/monitor.conf --log_dir=/apollo/data/log
autostart=false
......
......@@ -115,17 +115,6 @@ autorestart=unexpected
redirect_stderr=true
stdout_logfile=/apollo/data/log/dreamview.out
[program:sim_control]
command=/apollo/modules/dreamview/dreamview --flagfile=/apollo/modules/dreamview/conf/dreamview.conf --enable_sim_control --log_dir=/apollo/data/log
autostart=false
numprocs=1
exitcodes=0
stopsignal=SIGINT
startretries=10
autorestart=unexpected
redirect_stderr=true
stdout_logfile=/apollo/data/log/dreamview.out
[program:monitor]
command=/apollo/modules/monitor/monitor --flagfile=/apollo/modules/monitor/conf/monitor.conf --log_dir=/apollo/data/log
autostart=false
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册