Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
8030aad8
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
8030aad8
编写于
8月 01, 2017
作者:
A
Aaron Xiao
提交者:
Jiangtao Hu
8月 01, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Migrate ros_node_service into HMI and avoid GRPC.
上级
8a4e2e98
变更
8
隐藏空白更改
内联
并排
Showing
8 changed file
with
35 addition
and
288 deletion
+35
-288
apollo.sh
apollo.sh
+1
-2
modules/hmi/proto/BUILD
modules/hmi/proto/BUILD
+0
-12
modules/hmi/proto/ros_node.proto
modules/hmi/proto/ros_node.proto
+0
-26
modules/hmi/ros_node/BUILD
modules/hmi/ros_node/BUILD
+0
-22
modules/hmi/ros_node/ros_node_service.cc
modules/hmi/ros_node/ros_node_service.cc
+0
-188
modules/hmi/web/ros_service_api.py
modules/hmi/web/ros_service_api.py
+33
-27
modules/tools/py27_requirements.txt
modules/tools/py27_requirements.txt
+0
-2
scripts/hmi.sh
scripts/hmi.sh
+1
-9
未找到文件。
apollo.sh
浏览文件 @
8030aad8
...
...
@@ -197,8 +197,7 @@ function release() {
cp
-r
modules/common/data
$MODULES_DIR
/common
# hmi
mkdir
-p
$MODULES_DIR
/hmi/ros_node
$MODULES_DIR
/hmi/utils
cp
bazel-bin/modules/hmi/ros_node/ros_node_service
$MODULES_DIR
/hmi/ros_node/
mkdir
-p
$MODULES_DIR
/hmi/utils
cp
-r
modules/hmi/conf
$MODULES_DIR
/hmi
cp
-r
modules/hmi/web
$MODULES_DIR
/hmi
cp
-r
modules/hmi/utils/
*
.py
$MODULES_DIR
/hmi/utils
...
...
modules/hmi/proto/BUILD
浏览文件 @
8030aad8
...
...
@@ -17,15 +17,3 @@ py_proto_compile(
name
=
"runtime_status_proto_pylib"
,
protos
=
[
"runtime_status.proto"
],
)
cc_proto_library
(
name
=
"ros_node_proto"
,
protos
=
[
"ros_node.proto"
],
with_grpc
=
True
,
)
py_proto_compile
(
name
=
"ros_node_proto_pylib"
,
protos
=
[
"ros_node.proto"
],
with_grpc
=
True
,
)
modules/hmi/proto/ros_node.proto
已删除
100644 → 0
浏览文件 @
8a4e2e98
syntax
=
"proto2"
;
package
apollo
.
hmi
;
service
HMIRosNode
{
rpc
ChangeDrivingMode
(
ChangeDrivingModeRequest
)
returns
(
ChangeDrivingModeResponse
)
{}
}
message
ChangeDrivingModeRequest
{
enum
Action
{
RESET_TO_MANUAL
=
1
;
START_TO_AUTO
=
2
;
}
optional
Action
action
=
1
;
}
message
ChangeDrivingModeResponse
{
enum
Result
{
UNKNOWN
=
1
;
SUCCESS
=
2
;
FAIL
=
3
;
}
optional
Result
result
=
1
;
}
modules/hmi/ros_node/BUILD
已删除
100644 → 0
浏览文件 @
8a4e2e98
load
(
"//tools:cpplint.bzl"
,
"cpplint"
)
package
(
default_visibility
=
[
"//visibility:public"
])
cc_binary
(
name
=
"ros_node_service"
,
srcs
=
[
"ros_node_service.cc"
,
],
deps
=
[
"//external:gflags"
,
"//modules/canbus/proto:canbus_proto"
,
"//modules/common/adapters:adapter_manager"
,
"//modules/control/common"
,
"//modules/control/proto:control_proto"
,
"//modules/hmi/proto:ros_node_proto"
,
"@com_github_google_protobuf//:protobuf"
,
"@ros//:ros_common"
,
],
)
cpplint
()
modules/hmi/ros_node/ros_node_service.cc
已删除
100644 → 0
浏览文件 @
8a4e2e98
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include <chrono>
#include <memory>
#include <mutex>
#include <thread>
#include "gflags/gflags.h"
#include "grpc++/security/server_credentials.h"
#include "grpc++/server.h"
#include "grpc++/server_builder.h"
#include "modules/canbus/proto/chassis.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/log.h"
#include "modules/control/common/control_gflags.h"
#include "modules/control/proto/pad_msg.pb.h"
#include "modules/hmi/proto/ros_node.grpc.pb.h"
DEFINE_string
(
hmi_ros_node_service_address
,
"127.0.0.1:8897"
,
"HMI Ros node service address."
);
using
apollo
::
common
::
adapter
::
AdapterConfig
;
using
apollo
::
common
::
adapter
::
AdapterManager
;
using
apollo
::
common
::
adapter
::
AdapterManagerConfig
;
using
apollo
::
control
::
DrivingAction
;
using
apollo
::
canbus
::
Chassis
;
namespace
apollo
{
namespace
hmi
{
namespace
{
static
constexpr
char
kHMIRosNodeName
[]
=
"hmi_ros_node_service"
;
void
SendPadMessage
(
DrivingAction
action
)
{
control
::
PadMessage
pad
;
pad
.
set_action
(
action
);
AINFO
<<
"Sending PadMessage:
\n
"
<<
pad
.
DebugString
();
AdapterManager
::
FillPadHeader
(
kHMIRosNodeName
,
&
pad
);
AdapterManager
::
PublishPad
(
pad
);
}
/**
* @class HMIRosNodeImpl
*
* @brief Implementation of HMIRosNode service.
*/
class
HMIRosNodeImpl
final
:
public
HMIRosNode
::
Service
{
public:
/*
* @brief Init the ROS node.
*/
static
void
Init
()
{
// Setup AdapterManager.
AdapterManagerConfig
config
;
config
.
set_is_ros
(
true
);
{
auto
*
sub_config
=
config
.
add_config
();
sub_config
->
set_mode
(
AdapterConfig
::
PUBLISH_ONLY
);
sub_config
->
set_type
(
AdapterConfig
::
PAD
);
}
{
auto
*
sub_config
=
config
.
add_config
();
sub_config
->
set_mode
(
AdapterConfig
::
RECEIVE_ONLY
);
sub_config
->
set_type
(
AdapterConfig
::
CHASSIS
);
}
AdapterManager
::
Init
(
config
);
AdapterManager
::
SetChassisCallback
(
MonitorDrivingMode
);
}
/*
* @brief Implementation of ChangeDrivingMode RPC.
* @param context a pointer to the grpc context
* @param request a pointer to an instance of ChangeDrivingModeRequest
* @param response a pointer to an instance of ChangeDrivingModeResponse
* @return the grpc status
*/
grpc
::
Status
ChangeDrivingMode
(
grpc
::
ServerContext
*
context
,
const
ChangeDrivingModeRequest
*
request
,
ChangeDrivingModeResponse
*
response
)
override
{
AINFO
<<
"received ChangeDrivingModeRequest: "
<<
request
->
DebugString
();
auto
driving_action_to_send
=
DrivingAction
::
RESET
;
auto
driving_mode_to_wait
=
Chassis
::
COMPLETE_MANUAL
;
switch
(
request
->
action
())
{
case
ChangeDrivingModeRequest
::
RESET_TO_MANUAL
:
// Default action and mode.
break
;
case
ChangeDrivingModeRequest
::
START_TO_AUTO
:
driving_action_to_send
=
DrivingAction
::
START
;
driving_mode_to_wait
=
Chassis
::
COMPLETE_AUTO_DRIVE
;
break
;
default:
response
->
set_result
(
ChangeDrivingModeResponse
::
UNKNOWN
);
return
grpc
::
Status
(
grpc
::
StatusCode
::
UNKNOWN
,
"Unknown ChangeDrivingMode action."
);
}
constexpr
int
kMaxTries
=
5
;
constexpr
auto
kTryInterval
=
std
::
chrono
::
milliseconds
(
500
);
auto
result
=
ChangeDrivingModeResponse
::
FAIL
;
for
(
int
i
=
0
;
i
<
kMaxTries
;
++
i
)
{
// Send driving action periodically until entering target driving mode.
SendPadMessage
(
driving_action_to_send
);
std
::
this_thread
::
sleep_for
(
kTryInterval
);
std
::
lock_guard
<
std
::
mutex
>
guard
(
current_driving_mode_mutex_
);
if
(
current_driving_mode_
==
driving_mode_to_wait
)
{
result
=
ChangeDrivingModeResponse
::
SUCCESS
;
break
;
}
}
response
->
set_result
(
result
);
AINFO
<<
"ChangeDrivingModeResponse: "
<<
response
->
DebugString
();
if
(
result
==
ChangeDrivingModeResponse
::
FAIL
)
{
AERROR
<<
"Failed to change driving mode to "
<<
request
->
DebugString
();
}
return
grpc
::
Status
::
OK
;
}
private:
// Monitor the driving mode by listening to Chassis message.
static
void
MonitorDrivingMode
(
const
Chassis
&
status
)
{
auto
driving_mode
=
status
.
driving_mode
();
std
::
lock_guard
<
std
::
mutex
>
guard
(
current_driving_mode_mutex_
);
// Update current_driving_mode_ when it is changed.
if
(
driving_mode
!=
current_driving_mode_
)
{
AINFO
<<
"Found Chassis DrivingMode changed: "
<<
Chassis_DrivingMode_Name
(
current_driving_mode_
)
<<
" -> "
<<
Chassis_DrivingMode_Name
(
driving_mode
);
current_driving_mode_
=
driving_mode
;
}
}
static
std
::
mutex
current_driving_mode_mutex_
;
static
Chassis
::
DrivingMode
current_driving_mode_
;
};
// Init static members.
std
::
mutex
HMIRosNodeImpl
::
current_driving_mode_mutex_
;
Chassis
::
DrivingMode
HMIRosNodeImpl
::
current_driving_mode_
=
Chassis
::
COMPLETE_MANUAL
;
void
RunGRPCServer
()
{
// Start GRPC service.
HMIRosNodeImpl
service
;
grpc
::
ServerBuilder
builder
;
builder
.
AddListeningPort
(
FLAGS_hmi_ros_node_service_address
,
grpc
::
InsecureServerCredentials
());
builder
.
RegisterService
(
&
service
);
std
::
unique_ptr
<
grpc
::
Server
>
server
(
builder
.
BuildAndStart
());
AINFO
<<
"Server listening on "
<<
FLAGS_hmi_ros_node_service_address
;
server
->
Wait
();
}
}
// namespace
}
// namespace hmi
}
// namespace apollo
int
main
(
int
argc
,
char
**
argv
)
{
google
::
InitGoogleLogging
(
argv
[
0
]);
google
::
ParseCommandLineFlags
(
&
argc
,
&
argv
,
true
);
// Setup ros node.
ros
::
init
(
argc
,
argv
,
::
apollo
::
hmi
::
kHMIRosNodeName
);
::
apollo
::
hmi
::
HMIRosNodeImpl
::
Init
();
// Run GRPC server in background thread.
std
::
thread
grpc_server_thread
(
::
apollo
::
hmi
::
RunGRPCServer
);
ros
::
spin
();
grpc_server_thread
.
join
();
return
0
;
}
modules/hmi/web/ros_service_api.py
浏览文件 @
8030aad8
...
...
@@ -20,49 +20,35 @@
import
httplib
import
flask_restful
import
gflags
import
glog
import
grpc
import
rospy
import
modules.hmi.proto.ros_node_pb2
as
ros_node_pb2
import
modules.
hmi.proto.runtime_status_pb2
as
runtime_status
_pb2
from
modules.hmi.proto.runtime_status_pb2
import
ToolStatus
import
modules.
control.proto.pad_msg_pb2
as
pad_msg
_pb2
import
runtime_status
gflags
.
DEFINE_string
(
'hmi_ros_node_service'
,
'127.0.0.1:8897'
,
'Address of HMI ros node grpc service.'
)
class
RosServiceApi
(
flask_restful
.
Resource
):
"""HMI ros node service."""
pad_msg_pub
=
None
pad_msg_seq_num
=
0
def
get
(
self
,
cmd_name
):
"""Run ros command
by sending GRPC requests
and return HTTP response."""
"""Run ros command and return HTTP response."""
return
RosServiceApi
.
execute_cmd
(
cmd_name
)
@
staticmethod
def
execute_cmd
(
cmd_name
):
"""Run ros command by sending GRPC requests and return HTTP response."""
ToolStatus
=
runtime_status_pb2
.
ToolStatus
channel
=
grpc
.
insecure_channel
(
gflags
.
FLAGS
.
hmi_ros_node_service
)
stub
=
ros_node_pb2
.
HMIRosNodeStub
(
channel
)
response
=
None
@
classmethod
def
execute_cmd
(
cls
,
cmd_name
):
"""Run ros command and return HTTP response."""
status
=
runtime_status
.
RuntimeStatus
tool_status
=
status
.
get_tools
()
if
cmd_name
==
'reset'
:
request
=
ros_node_pb2
.
ChangeDrivingModeRequest
(
action
=
ros_node_pb2
.
ChangeDrivingModeRequest
.
RESET_TO_MANUAL
)
response
=
stub
.
ChangeDrivingMode
(
request
)
cls
.
perform_driving_action
(
pad_msg_pb2
.
RESET
)
# Update runtime status.
if
tool_status
.
playing_status
!=
ToolStatus
.
PLAYING_NOT_READY
:
tool_status
.
playing_status
=
ToolStatus
.
PLAYING_READY_TO_CHECK
elif
cmd_name
==
'start_auto_driving'
:
request
=
ros_node_pb2
.
ChangeDrivingModeRequest
(
action
=
ros_node_pb2
.
ChangeDrivingModeRequest
.
START_TO_AUTO
)
response
=
stub
.
ChangeDrivingMode
(
request
)
cls
.
perform_driving_action
(
pad_msg_pb2
.
START
)
# Update runtime status.
if
tool_status
.
playing_status
==
ToolStatus
.
PLAYING_READY_TO_START
:
tool_status
.
playing_status
=
ToolStatus
.
PLAYING
...
...
@@ -72,6 +58,26 @@ class RosServiceApi(flask_restful.Resource):
return
error_msg
,
httplib
.
BAD_REQUEST
status
.
broadcast_status_if_changed
()
glog
.
info
(
'Processed command "{}", and get response:{}'
.
format
(
cmd_name
,
response
))
glog
.
info
(
'Processed command "{}"'
.
format
(
cmd_name
))
return
'OK'
,
httplib
.
OK
@
classmethod
def
perform_driving_action
(
cls
,
driving_action
):
"""Request to perform driving action."""
if
cls
.
pad_msg_pub
is
None
:
rospy
.
init_node
(
'hmi_ros_node_service'
,
anonymous
=
True
)
cls
.
pad_msg_pub
=
rospy
.
Publisher
(
'/apollo/control/pad'
,
pad_msg_pb2
.
PadMessage
,
queue_size
=
1
)
pad_msg
=
pad_msg_pb2
.
PadMessage
()
pad_msg
.
header
.
timestamp_sec
=
rospy
.
get_time
()
pad_msg
.
header
.
module_name
=
"hmi_ros_node_service"
pad_msg
.
action
=
driving_action
# Send pad message 3 times.
for
_
in
range
(
3
):
cls
.
pad_msg_seq_num
+=
1
pad_msg
.
header
.
sequence_num
=
cls
.
pad_msg_seq_num
glog
.
info
(
'Publishing message: {}'
.
format
(
pad_msg
))
cls
.
pad_msg_pub
.
publish
(
pad_msg
)
rospy
.
sleep
(
0.5
)
modules/tools/py27_requirements.txt
浏览文件 @
8030aad8
...
...
@@ -5,8 +5,6 @@
# Google infras.
glog
google-apputils
grpc >= 0.3
grpcio
protobuf == 3.1
python-gflags
...
...
scripts/hmi.sh
浏览文件 @
8030aad8
...
...
@@ -28,13 +28,6 @@ function start() {
ROSCORELOG
=
"
${
APOLLO_ROOT_DIR
}
/data/log/roscore.out"
nohup
roscore </dev/null
>
"
${
ROSCORELOG
}
"
2>&1 &
echo
"HMI ros node service running at localhost:8887"
LOG
=
"
${
APOLLO_ROOT_DIR
}
/data/log/hmi_ros_node_service.out"
nohup
${
APOLLO_BIN_PREFIX
}
/modules/hmi/ros_node/ros_node_service
\
--v
=
3
\
--log_dir
=
${
APOLLO_ROOT_DIR
}
/data/log
\
>
${
LOG
}
2>&1 &
LOG
=
"
${
APOLLO_ROOT_DIR
}
/data/log/hmi.out"
nohup
python modules/hmi/web/hmi_main.py
\
--conf
=
modules/hmi/conf/config.pb.txt
>
"
${
LOG
}
"
2>&1 &
...
...
@@ -50,8 +43,7 @@ function start() {
}
function
stop
()
{
pkill
-f
hmi_main.py
pkill
-f
ros_node_service
pkill
-f
-9
hmi_main.py
pkill
-f
roscore
}
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录