Commit 29efd221 authored by yangxue's avatar yangxue

update msgs

parent 7c0fd42f
geometry_msgs/PolygonStamped Polygon
int32 obs_type
Header header
CameraObstacle[] obstacles
std_msgs/Header header
geometry_msgs/Point[] points
std_msgs/Header header
uint32 id
string label
float64 score
sensor_msgs/PointCloud2 cloud
geometry_msgs/PointStamped min_point
geometry_msgs/PointStamped max_point
geometry_msgs/PointStamped avg_point
geometry_msgs/PointStamped centroid_point
float64 estimated_angle
geometry_msgs/Vector3 dimensions
geometry_msgs/Vector3 eigen_values
geometry_msgs/Vector3[] eigen_vectors
#Array of 33 floats containing the FPFH descriptor
std_msgs/Float32MultiArray fpfh_descriptor
jsk_recognition_msgs/BoundingBox bounding_box
geometry_msgs/PolygonStamped convex_hull
# Indicator information
# INDICATOR_LEFT 0
# INDICATOR_RIGHT 1
# INDICATOR_BOTH 2
# INDICATOR_NONE 3
uint32 indicator_state
\ No newline at end of file
std_msgs/Header header
CloudCluster[] clusters
\ No newline at end of file
Header header
# ESR Track Msg
string canmsg
uint8 cluster_id
float32 cluster_dist_long
float32 cluster_dist_lat
float32 cluster_v_rel_long
float32 cluster_v_rel_lat
uint8 cluster_dyn_prop
float32 radar_RCS
\ No newline at end of file
Header header
ContinentRadarTrack[] ContinentRadarTrack
int32 id
string type
float64 x
float64 y
float64 z
float64 w
float64 h
float64 prob
Header header
int32 num_objects
DetectBoxMsg[] objectsArr
\ No newline at end of file
Header header
# ESR Track Msg
string canmsg
uint8 track_ID
float32 track_lat_rate
bool track_group_changed
uint8 track_status
float32 track_angle
float32 track_range
bool track_bridge_object
bool track_rolling_count
float32 track_width
float32 track_range_accel
uint8 track_med_range_mode
float32 track_range_rate
Header header
# ESR Track Msg
EsrTrack[] esrtrack
Header header
string msgname
uint8 track_id
uint8 track_type
float32 track_rate
float32 track_rate_lat
float32 track_heading
jsk_recognition_msgs/BoundingBox bounding_box
geometry_msgs/Point[] track_trace
geometry_msgs/PolygonStamped Polygon
bool is_obstacle
bool is_static
geometry_msgs/Point obs_ref_path_point
int32 point_cloud_amout
Header header
ObjectTrack[] object_track
geometry_msgs/Pose vehicle_pose
\ No newline at end of file
float64 obsSize
float64 x_min
float64 x_max
float64 y_min
float64 y_max
float64 z_min
float64 z_max
float64 distance_min
int32 cluster
int32 pointNum
int32 obsType
float64 speed
Header header
float64 cellLength
float64 cellWidth
Obstacle[] obstacles
Header header
float32 cell_length
float32 cell_width
float32[] x
float32[] y
float32[] z
#子系统自接收到硬件数据的时刻,到发出去算法处理结果之间的耗时,将计算结果放到msg中发出去,跟随心跳发出
#单位为秒
float64 sub_sys_process_time_consume
#从main进入到第一个有效数据发出去的耗时
#单位为秒
float64 sub_sys_start_up_time_consume
Header header
geometry_msgs/Pose vehicle_pose
sensor_msgs/PointCloud2 beyond_cloud
\ No newline at end of file
# Message file for srr_track
Header header
uint8 CAN_TX_DETECT_VALID_LEVEL
uint8 CAN_TX_DETECT_VALID_LEVEL_Suspect_Detection=0
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_1=1
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_2=2
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_3=3
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_4=4
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_5=5
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_6=6
uint8 CAN_TX_DETECT_VALID_LEVEL_Level_7=7
bool CAN_TX_DETECT_STATUS
bool CAN_TX_DETECT_STATUS_No_Data=0
bool CAN_TX_DETECT_STATUS_Valid_Data_Present=1
float32 CAN_TX_DETECT_RANGE_RATE # m/s
float32 CAN_TX_DETECT_RANGE # m
float32 CAN_TX_DETECT_ANGLE # deg
float32 CAN_TX_DETECT_AMPLITUDE # dBsm
Header header
# SRR Track Msg
SrrTrack[] srrtrack
Header header
sensor_msgs/PointCloud2[] VCluster
geometry_msgs/PolygonStamped[] Polygon
bool[] is_obs
bool[] is_close_wall
geometry_msgs/Point[] obs_ref_point_array
int32[] point_cloud_amout_array
geometry_msgs/Pose vehicle_pose
Header header
uint32 id
uint8 direction
uint32 timeflag
uint8 sendtype
uint8 remoteflag
uint8 externflag
uint8 datalen
uint8[8] data
uint32 id
string type
float64 x
float64 y
float64 z
float64 w
float64 h
float64 prob
# topic name : lightros
Header header
lightros[] lightObjS
\ No newline at end of file
int32 motionFlag
\ No newline at end of file
Header header
SecurityCommon security_common
float32 perception_delay #感知系统延时
float32 perception_back_delay #后方感知系统延时
bool point_cloud_error_device1 #前方velodyne lidar数据是否异常
bool point_cloud_error_device2 #前方sick 1 lidar数据是否异常
bool point_cloud_error_device3 #前方sick 2 lidar数据是否异常
bool point_cloud_error_device4 #前方esr lidar数据是否异常
bool point_cloud_error_device5 #前方srr 1 lidar数据是否异常
bool point_cloud_error_device6 #前方srr 2 lidar数据是否异常
bool point_cloud_error_device7 #后方 lidar数据是否异常
bool point_cloud_error_device8 #后方radar数据是否异常
bool perception_status #前方感知系统是否异常
bool perception_back_status #后方感知系统是否异常
float32 error_detect_ratio #误检率
\ No newline at end of file
Header header
uint8 box_num
float32[] x1
float32[] x2
float32[] x3
float32[] x4
float32[] y1
float32[] y2
float32[] y3
float32[] y4
cmake_minimum_required(VERSION 2.8.3)
project(waytous_perception_msgs)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
message_generation
message_runtime
nav_msgs
std_msgs
# grid_map_msgs
roscpp
sensor_msgs
tf
tf2
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
add_message_files(
FILES
Rect.msg
# FlatnessMap.msg
NormalMap.msg
Object.msg
ObjectArray.msg
ObjectTemp.msg
ObjectArrayTemp.msg
Road.msg
RoadArray.msg
Scene.msg
WallMap.msg
FleetObject.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
geometry_msgs
nav_msgs
sensor_msgs
std_msgs
# grid_map_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS
# LIBRARIES waytous_perception_msgs
CATKIN_DEPENDS geometry_msgs std_msgs message_generation message_runtime sensor_msgs nav_msgs roscpp sensor_msgs tf tf2
# DEPENDS system_lib
) # remvoe grid_map_msgs
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
#include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/waytous_perception_msgs.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/waytous_perception_msgs_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_waytous_perception_msgs.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
Header header
grid_map_msgs/GridMap elevation_map #高程图
grid_map_msgs/GridMap flatness_map #平整度信息图
grid_map_msgs/GridMap slope_map #坡度地图
grid_map_msgs/GridMap occupancy_map #可行驶区域
#---------------------fitness_level--------------------
int8 FLATNESS_LEVEL0 = 0
int8 FLATNESS_LEVEL1 = 1
int8 FLATNESS_LEVEL2 = 2
int8 FLATNESS_LEVEL3 = 3
int8 FLATNESS_LEVEL4 = 4
#---------------------occupancy_level--------------------
int8 OCC_UNKNOWN = 0
int8 OCC_FREE = 1
int8 OCC_MOVABLE = 2
int8 OCC_STATIC = 3
Header header
int8 weather_type # 天气
int8 light_type # 光照条件
int8 place_type # 地点
#-------------------weather_type-----------------
int8 WEATHER_UNKNOWN = 0 # 未知
int8 WEATHER_SUNNY = 1 # 晴天
int8 WEATHER_CLOUDY = 2 # 多云
int8 WEATHER_RAINY = 3 # 雨天
int8 WEATHER_HAZE = 4 # 雾霾
int8 WEATHER_SNOWY = 5 # 雪天
int8 LIGHT_DAYTIME = 0 # 白天
int8 LIGHT_DUSK = 1 # 黄昏
int8 LIGHT_NIGHT = 2 # 晚上
#-------------------place_type-----------------
int8 PLACE_COMMON_ROAD = 0
int8 PLACE_PARKING_SPACE = 1
int8 PLACE_CROSSWALK = 2
int8 PLACE_GAS_STATION = 3
int8 PLACE_WEIGHT_STATION = 4
std_msgs/Header header
waytous_perception_msgs/ObjectArray objects
waytous_perception_msgs/DrivableAreaMap maps
waytous_perception_msgs/DrivingScene scene
waytous_perception_msgs/TrafficLight[] trafficlight_array
Header header
grid_map_msgs/GridMap elevation_map #高程图
grid_map_msgs/GridMap flatness_map #平整度信息图
#---------------------fitness_level--------------------
int8 FLATNESS_LEVEL0 = 0
int8 FLATNESS_LEVEL1 = 1
int8 FLATNESS_LEVEL2 = 2
int8 FLATNESS_LEVEL3 = 3
int8 FLATNESS_LEVEL4 = 4
int8 id # 车辆ID, required
int8 property # 车辆归属, required
int16 weight # 车辆重量
geometry_msgs/Pose pose # 车辆定位, required
geometry_msgs/Vector3 dimensions # 车辆大小
geometry_msgs/Vector3 velocity # 车辆速度, required
geometry_msgs/Vector3 accelerate # 车辆加速度
int8[] next_map_id # 未来行驶的路径ID
float32[] id_probs # 预测可能性
#---------------------property--------------------
int8 PROPERTY_OUTSIDER = 0 # 缺省为非系统内车辆
int8 PROPERTY_MGV = 1 # 系统内有人车
int8 PROPERTY_UGV = 2 # 系统内无人车
std_msgs/Header header
FleetObject[] fleet_object_list
\ No newline at end of file
Header header
float32 ogmwidth #二维栅格地图宽
float32 ogmheight #二维栅格地图高
int16 vehicle_x #车辆在栅格图中的水平位置
int16 vehicle_y #车辆在栅格图中的竖直位置
float32 rectangle_minx #拟合矩形左边界
float32 rectangle_maxx #拟合矩形右边界
float32 rectangle_miny #拟合矩形下边界
float32 rectangle_maxy #拟合矩形上边界
float32 slopeupdegree #坡度值
float32 slopedestination #斜坡方向(0-360度)
bool vehiclepositionflag #斜坡类型(可用来判断是否为斜坡点,及正坡/负坡)
geometry_msgs/Vector3 normal #normal
sensor_msgs/PointCloud2 pointcloud_with_normal
int8 id # Object ID, required
int8 property # vehicle property, optional
float32 exist_prob # exist probability
############### 2D Rect
waytous_perception_msgs/Rect obb2d # [x,y,w,h,orientation], required
############### 3D Dimension
geometry_msgs/Pose pose # the pose of the center of the object, position is required, quaternion is optional
geometry_msgs/Vector3 dimensions # required
geometry_msgs/Polygon convex_hull # the hull of the obejct, required
sensor_msgs/PointCloud2 cloud # the cloud of the obejct, option
############### classification info
int8 type # major type, optional
float32[] type_probs
int8 sub_type # sub type, optional
float32[] sub_type_probs
############### tracking info
int8 track_id # required
geometry_msgs/Vector3 velocity # required
float32[] velocity_covariance # optional
geometry_msgs/Vector3 accelerate # required
geometry_msgs/Vector3[] trace # optional
geometry_msgs/Vector3[] trajectory # optional
FleetObject fleet_object # optional
#---------------------major_type--------------------
int8 TYPE_UNKNOWN = 0
int8 TYPE_PEDESTRIAN = 1
int8 TYPE_BICYCLE = 2
int8 TYPE_VEHICLE = 3
int8 TYPE_MACHINERY = 4
int8 TYPE_UNKNOWN_MOVABLE = 5
int8 TYPE_UNKNOWN_STATIC = 6
#---------------------sub_type--------------------
int8 SUBTYPE_UNKNOWN = 0
int8 SUBTYPE_CAR = 1
int8 SUBTYPE_VAN = 2
int8 SUBTYPE_TRUCK = 3
int8 SUBTYPE_DUMPER = 4
int8 SUBTYPE_FLUSHER = 5
int8 SUBTYPE_DOZER = 6
int8 SUBTYPE_EXCAVATOR = 7
int8 SUBTYPE_CYCLIST = 8
int8 SUBTYPE_MOTORCYCLIST = 9
int8 SUBTYPE_TRICYCLIST = 10
int8 SUBTYPE_PEDESTRIAN = 11
int8 SUBTYPE_TRAFFIC_CONE = 12
int8 SUBTYPE_UNKNOWN_MOVABLE = 13
int8 SUBTYPE_UNKNOWN_STATIC = 14
#---------------------property--------------------
int8 PROPERTY_OUTSIDER = 0
int8 PROPERTY_MGV = 1
int8 PROPERTY_UGV = 2
Header header
int8 sensor_type # Object sensor source, required
sensor_msgs/Image image
waytous_perception_msgs/Object[] foreground_objects
waytous_perception_msgs/Object[] background_objects
#---------------------sensor_type--------------------
int8 SENSOR_INVALID = 0
int8 SENSOR_RADAR = 1
int8 SENSOR_LIDAR = 2
int8 SENSOR_CAMERA = 4
int8 SENSOR_VEHICLE = 8
int8 SENSOR_V2X = 16
int8 SENSOR_FLEET = 32
\ No newline at end of file
Header header
sensor_msgs/Image roi_image
waytous_perception_msgs/ObjectTemp[] foreground_objects
waytous_perception_msgs/ObjectTemp[] background_objects
waytous_perception_msgs/Scene current_scene
int8 id # Object ID, required
int8 property # vehicle property, optional
float32 exist_prob # exist probability
############### 2D Rect
waytous_perception_msgs/Rect obb2d # [x,y,w,h,orientation], required
############### 3D Dimension
geometry_msgs/Pose pose # the pose of the center of the object, position is required, quaternion is optional
geometry_msgs/Vector3 dimensions # required
geometry_msgs/Polygon convex_hull # the hull of the obejct, required
sensor_msgs/PointCloud2 cloud # the cloud of the obejct, option
############### classification info
int8 type # major type, optional
float32[] type_probs
int8 sub_type # sub type, optional
float32[] sub_type_probs
############### tracking info
uint32 track_id # required
geometry_msgs/Vector3 velocity # required
float32[] velocity_covariance # optional
geometry_msgs/Vector3 accelerate # required
geometry_msgs/Vector3[] trace # optional
geometry_msgs/Vector3[] trajectory # optional
FleetObject fleet_object # optional
#---------------------major_type--------------------
int8 TYPE_UNKNOWN = 0
int8 TYPE_PEDESTRIAN = 1
int8 TYPE_BICYCLE = 2
int8 TYPE_VEHICLE = 3
int8 TYPE_MACHINERY = 4
int8 TYPE_UNKNOWN_MOVABLE = 5
int8 TYPE_UNKNOWN_STATIC = 6
#---------------------sub_type--------------------
int8 SUBTYPE_UNKNOWN = 0
int8 SUBTYPE_CAR = 1
int8 SUBTYPE_VAN = 2
int8 SUBTYPE_TRUCK = 3
int8 SUBTYPE_DUMPER = 4
int8 SUBTYPE_FLUSHER = 5
int8 SUBTYPE_DOZER = 6
int8 SUBTYPE_EXCAVATOR = 7
int8 SUBTYPE_CYCLIST = 8
int8 SUBTYPE_MOTORCYCLIST = 9
int8 SUBTYPE_TRICYCLIST = 10
int8 SUBTYPE_PEDESTRIAN = 11
int8 SUBTYPE_TRAFFIC_CONE = 12
int8 SUBTYPE_UNKNOWN_MOVABLE = 13
int8 SUBTYPE_UNKNOWN_STATIC = 14
#---------------------property--------------------
int8 PROPERTY_OUTSIDER = 0
int8 PROPERTY_MGV = 1
int8 PROPERTY_UGV = 2
int8 MOTION_UNKNOWN = 0
int8 MOTION_MOVING = 1
int8 MOTION_STATIONARY = 2
float64 x
float64 y
float64 w
float64 h
float64 orientation
int8 label
geometry_msgs/Vector3[] points
#---------------------label--------------------
int8 TYPE_ROAD = 0
int8 TYPE_ROAD_EDGE = 1
int8 TYPE_NON_ROAD = 2
Header header
waytous_perception_msgs/Road[] road_list
Header header
int8 type
waytous_perception_msgs/Rect rect
float64 reliable
#---------------------type--------------------
int8 TYPE_NORMAL = 0
int8 TYPE_FOG = 1
int8 TYPE_DUST = 2
int8 TYPE_RAIN = 3
int8 TYPE_SNOW = 4
int8 TYPE_DARK = 5
int8 TYPE_TRAFFIC_LIGHT_GREEN = 6
int8 TYPE_TRAFFIC_LIGHT_RED = 7
int8 TYPE_TRAFFIC_LIGHT_YELLOW = 8
int8 TYPE_TRAFFIC_LIGHT_UNKNOWN = 9
std_msgs/Header header
string id # 地图红绿灯ID
int8 sensor_type # 信息来源
int8 color # 红绿灯颜色
waytous_perception_msgs/Rect rect # 红绿灯二维位置
geometry_msgs/Polygon polygon # 红绿灯三维位置
int8 confidence # 检测置信度
float32 remaining_time # 剩余时间
#----------------sensor_type--------------------------
int8 SENSOR_INVALID = 0
int8 SENSOR_CAMERA = 1
int8 SENSOR_V2X = 2
#----------------color--------------------------
int8 COLOR_UNKNOWN = 0
int8 COLOR_RED = 1
int8 COLOR_YELLOW = 2
int8 COLOR_GREEN = 3
int8 COLOR_BLACK = 4
std_msgs/Header header
int16 ogmwidth #二维栅格地图宽
int16 ogmheight #二维栅格地图高
int16 vehicle_x #车辆在栅格图中的水平位置
int16 vehicle_y #车辆在栅格图中的竖直位置
float32 ogmresolution #栅格分辨率
int16[] data #栅格点(像素为1和2的栅格为挡墙)
\ No newline at end of file
<?xml version="1.0"?>
<package format="2">
<name>waytous_perception_msgs</name>
<version>0.0.0</version>
<description>The waytous_perception_msgs package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="yul@todo.todo">yul</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/waytous_perception_msgs</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>message_runtime</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf2</build_depend>
<build_depend>grid_map_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>grid_map_msgs</build_export_depend>
<build_export_depend>nav_msgs</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>tf</build_export_depend>
<build_export_depend>tf2</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>grid_map_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>tf2</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>message_generation</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment