Skip to content
Projects
Groups
Snippets
Help
This project
Loading...
Sign in / Register
Toggle navigation
R
ros_camera_bev
Project
Project
Details
Activity
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Board
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
yangxue
ros_camera_bev
Commits
37dee9a5
Commit
37dee9a5
authored
Mar 20, 2024
by
xin.wang.waytous
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
high-filter
parent
6150ca42
Show whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
7 additions
and
8 deletions
+7
-8
CameraBevParam.yaml
src/camera_bev_infer/configs/CameraBevParam.yaml
+2
-2
CameraBevParam_jd06.yaml
src/camera_bev_infer/configs/CameraBevParam_jd06.yaml
+1
-1
vision_3d.cpp
src/camera_bev_infer/src/vision_transform/vision_3d.cpp
+4
-5
No files found.
src/camera_bev_infer/configs/CameraBevParam.yaml
View file @
37dee9a5
rgb_sub_topic_name
:
/sensor/camera/front_middle/image/bgr
rgb_sub_topic_name
:
/sensor/camera/front_middle/image/bgr
pointcloud_sub_topic_name
:
/total_calib_pointcloud
pointcloud_sub_topic_name
:
/total_calib_pointcloud
detection_pub_topic_name
:
/
perception/camera/obstacle
detection_pub_topic_name
:
/
camera/objects
# static_gridmap_pub_topic_name: /perception/camera/bev_static_gridmap
# static_gridmap_pub_topic_name: /perception/camera/bev_static_gridmap
creator_id
:
0000
creator_id
:
0000
creator_name
:
camera_bev_node
creator_name
:
camera_bev_node
...
@@ -15,7 +15,7 @@ vis_frame_id: Lidar
...
@@ -15,7 +15,7 @@ vis_frame_id: Lidar
vis_project
:
true
vis_project
:
true
# ["pedestrian", "vehicle", "stone"]
# ["pedestrian", "vehicle", "stone"]
pub_classes
:
[
"
stone"
,
"
cone"
]
pub_classes
:
[
"
stone"
,
"
cone"
]
obstacle_height_threshold
:
5
# cm
obstacle_height_threshold
:
2
5
# cm
camera_intrinsic
:
[
1346.61241105747
,
0
,
951.014999441565
,
camera_intrinsic
:
[
1346.61241105747
,
0
,
951.014999441565
,
0
,
1344.43795511862
,
530.562496955385
,
0
,
1344.43795511862
,
530.562496955385
,
0
,
0
,
1
]
0
,
0
,
1
]
...
...
src/camera_bev_infer/configs/CameraBevParam_jd06.yaml
View file @
37dee9a5
rgb_sub_topic_name
:
/front_rgb/image
rgb_sub_topic_name
:
/front_rgb/image
pointcloud_sub_topic_name
:
/total_calib_pointcloud
pointcloud_sub_topic_name
:
/total_calib_pointcloud
detection_pub_topic_name
:
/
perception/camera/obstacle
detection_pub_topic_name
:
/
camera/objects
# static_gridmap_pub_topic_name: /perception/camera/bev_static_gridmap
# static_gridmap_pub_topic_name: /perception/camera/bev_static_gridmap
creator_id
:
0000
creator_id
:
0000
creator_name
:
camera_bev_node
creator_name
:
camera_bev_node
...
...
src/camera_bev_infer/src/vision_transform/vision_3d.cpp
View file @
37dee9a5
...
@@ -5,7 +5,7 @@
...
@@ -5,7 +5,7 @@
* @Date: 2023-09-03 03:13:41
* @Date: 2023-09-03 03:13:41
* @email: xin.wang@waytous.com
* @email: xin.wang@waytous.com
* @LastEditors: wxin
* @LastEditors: wxin
* @LastEditTime: 2024-0
2-28 10:32:38
* @LastEditTime: 2024-0
3-12 06:38:25
*/
*/
...
@@ -1024,7 +1024,7 @@ int Visione_3D::Process_Instance_Objects(object_Seg_info& obj, const cv::Mat& in
...
@@ -1024,7 +1024,7 @@ int Visione_3D::Process_Instance_Objects(object_Seg_info& obj, const cv::Mat& in
}
}
}
}
bool
filtered
=
(
max_z
-
min_z
<
obstacle_height_threshold
*
0.01
)
&&
(
max_z
>
obstacle_height_threshold
*
0.01
*
0.5
);
bool
filtered
=
(
max_z
-
min_z
<
obstacle_height_threshold
*
0.01
)
||
(
max_z
<
obstacle_height_threshold
*
0.01
*
0.5
);
if
(
!
filtered
){
if
(
!
filtered
){
Tracks
[
obj
.
track_id
].
valid_frame_num
++
;
// add
Tracks
[
obj
.
track_id
].
valid_frame_num
++
;
// add
std
::
cout
<<
"------------------------ "
<<
obj
.
track_id
<<
": "
<<
obj
.
name
<<
" with "
<<
points3d
.
size
()
<<
std
::
cout
<<
"------------------------ "
<<
obj
.
track_id
<<
": "
<<
obj
.
name
<<
" with "
<<
points3d
.
size
()
<<
...
@@ -1050,9 +1050,6 @@ int Visione_3D::Process_Instance_Objects(object_Seg_info& obj, const cv::Mat& in
...
@@ -1050,9 +1050,6 @@ int Visione_3D::Process_Instance_Objects(object_Seg_info& obj, const cv::Mat& in
// 同时使用深度估计和点云投影来获取bev box
// 同时使用深度估计和点云投影来获取bev box
int
Visione_3D
::
Process_objects
(
const
cv
::
Mat
&
image
,
const
cv
::
Mat
&
depth
,
Cloud
::
Ptr
&
pcl_cloud
,
std
::
vector
<
object_Seg_info
>&
objs
,
BEV_GridMap
&
vGrid
){
int
Visione_3D
::
Process_objects
(
const
cv
::
Mat
&
image
,
const
cv
::
Mat
&
depth
,
Cloud
::
Ptr
&
pcl_cloud
,
std
::
vector
<
object_Seg_info
>&
objs
,
BEV_GridMap
&
vGrid
){
if
(
depth
.
empty
()){
return
Process_objects
(
image
,
pcl_cloud
,
objs
,
vGrid
);
}
if
(
pcl_cloud
==
nullptr
){
if
(
pcl_cloud
==
nullptr
){
return
Process_objects
(
image
,
depth
,
objs
,
vGrid
);
return
Process_objects
(
image
,
depth
,
objs
,
vGrid
);
}
}
...
@@ -1109,9 +1106,11 @@ int Visione_3D::Process_objects(const cv::Mat& image, const cv::Mat& depth, Clou
...
@@ -1109,9 +1106,11 @@ int Visione_3D::Process_objects(const cv::Mat& image, const cv::Mat& depth, Clou
int
res
=
Process_Instance_Objects
(
obj
,
point_index_in_camera
,
pcl_cloud
,
vGrid
);
int
res
=
Process_Instance_Objects
(
obj
,
point_index_in_camera
,
pcl_cloud
,
vGrid
);
if
(
res
==
-
1
){
// valid points太少,使用深度估计
if
(
res
==
-
1
){
// valid points太少,使用深度估计
// std::cout<<"using depth " << obj.name << "," <<obj.fConfidence<< std::endl;
// std::cout<<"using depth " << obj.name << "," <<obj.fConfidence<< std::endl;
if
(
!
depth
.
empty
()){
Process_Instance_Objects
(
obj
,
depth
,
pTable
,
vGrid
);
Process_Instance_Objects
(
obj
,
depth
,
pTable
,
vGrid
);
}
}
}
}
}
else
{
else
{
Process_Segmantic_Objects
(
obj
,
point_index_in_camera
,
pcl_cloud
,
vGrid
);
Process_Segmantic_Objects
(
obj
,
point_index_in_camera
,
pcl_cloud
,
vGrid
);
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment