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
3c675112
Commit
3c675112
authored
Apr 07, 2025
by
yangxue
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
use ObjectTrack
parent
3f371eb9
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
19 additions
and
6 deletions
+19
-6
common_maps.h
src/camera_bev_infer/src/common_maps.h
+4
-3
sensor_manager.cpp
src/camera_bev_infer/src/sensor_manager.cpp
+15
-3
No files found.
src/camera_bev_infer/src/common_maps.h
View file @
3c675112
...
@@ -5,7 +5,7 @@
...
@@ -5,7 +5,7 @@
* @Date: 2023-09-03 03:14:28
* @Date: 2023-09-03 03:14:28
* @email: xin.wang@waytous.com
* @email: xin.wang@waytous.com
* @LastEditors: yangxue xue.yang@waytous.com
* @LastEditors: yangxue xue.yang@waytous.com
* @LastEditTime: 2025-0
3-31 01:16:25
* @LastEditTime: 2025-0
4-07 03:49:19
*/
*/
#ifndef COMMON_MAP_H_
#ifndef COMMON_MAP_H_
...
@@ -27,9 +27,10 @@ static const cv::Scalar Perception_Default_Color = cv::Scalar(255, 255, 255);
...
@@ -27,9 +27,10 @@ static const cv::Scalar Perception_Default_Color = cv::Scalar(255, 255, 255);
static
const
int
Perception_Default_Maxsize
=
100
;
// m
static
const
int
Perception_Default_Maxsize
=
100
;
// m
static
std
::
map
<
std
::
string
,
int
>
name2type
=
{
static
std
::
map
<
std
::
string
,
int
>
name2type
=
{
{
"unknown"
,
waytous_perception_msgs
::
Object
::
TYPE_UNKNOWN
},
{
"pedestrian"
,
waytous_perception_msgs
::
Object
::
TYPE_PEDESTRIAN
},
{
"pedestrian"
,
waytous_perception_msgs
::
Object
::
TYPE_PEDESTRIAN
},
{
"vehicle"
,
waytous_perception_msgs
::
Object
::
TYPE_
TRUCK
},
{
"vehicle"
,
waytous_perception_msgs
::
Object
::
TYPE_
CAR
},
{
"stone"
,
waytous_perception_msgs
::
Object
::
TYPE_
UNKNOWN
}
{
"stone"
,
waytous_perception_msgs
::
Object
::
TYPE_
TRUCK
}
// {"two_wheel", waytous_perception_msgs::Object::TYPE_BICYCLE},
// {"two_wheel", waytous_perception_msgs::Object::TYPE_BICYCLE},
// {"car", waytous_perception_msgs::Object::TYPE_VEHICLE},
// {"car", waytous_perception_msgs::Object::TYPE_VEHICLE},
// {"truck", waytous_perception_msgs::Object::TYPE_VEHICLE},
// {"truck", waytous_perception_msgs::Object::TYPE_VEHICLE},
...
...
src/camera_bev_infer/src/sensor_manager.cpp
View file @
3c675112
...
@@ -5,7 +5,7 @@
...
@@ -5,7 +5,7 @@
* @Date: 2023-09-03 02:18:07
* @Date: 2023-09-03 02:18:07
* @email: xin.wang@waytous.com
* @email: xin.wang@waytous.com
* @LastEditors: yangxue xue.yang@waytous.com
* @LastEditors: yangxue xue.yang@waytous.com
* @LastEditTime: 2025-0
3-28 09:27:22
* @LastEditTime: 2025-0
4-07 03:55:10
*/
*/
...
@@ -52,7 +52,7 @@ sensorManager::sensorManager(ros::NodeHandle& nodehandle, ImageInferNodeParam& p
...
@@ -52,7 +52,7 @@ sensorManager::sensorManager(ros::NodeHandle& nodehandle, ImageInferNodeParam& p
// 初始化订阅、发布话题
// 初始化订阅、发布话题
image_subscriber_
=
nodehandle
.
subscribe
<
sensor_msgs
::
Image
>
(
param
.
rgb_sub_topic_name
,
1
,
boost
::
bind
(
&
sensorManager
::
updateImage
,
this
,
_1
));
image_subscriber_
=
nodehandle
.
subscribe
<
sensor_msgs
::
Image
>
(
param
.
rgb_sub_topic_name
,
1
,
boost
::
bind
(
&
sensorManager
::
updateImage
,
this
,
_1
));
pointcloud_subscriber_
=
nodehandle
.
subscribe
<
sensor_msgs
::
PointCloud2
>
(
param
.
pointcloud_sub_topic_name
,
1
,
boost
::
bind
(
&
sensorManager
::
updatePointcloud
,
this
,
_1
));
pointcloud_subscriber_
=
nodehandle
.
subscribe
<
sensor_msgs
::
PointCloud2
>
(
param
.
pointcloud_sub_topic_name
,
1
,
boost
::
bind
(
&
sensorManager
::
updatePointcloud
,
this
,
_1
));
obj_publisher_
=
nodehandle
.
advertise
<
waytous_perception_msgs
::
ObjectArray
>
(
param
.
detection_pub_topic_name
,
1
);
obj_publisher_
=
nodehandle
.
advertise
<
waytous_perception_msgs
::
Object
Track
Array
>
(
param
.
detection_pub_topic_name
,
1
);
pub_thread_
=
new
boost
::
thread
(
boost
::
bind
(
&
sensorManager
::
publishDetection
,
this
));
pub_thread_
=
new
boost
::
thread
(
boost
::
bind
(
&
sensorManager
::
publishDetection
,
this
));
};
};
...
@@ -179,6 +179,8 @@ void sensorManager::publishDetection()
...
@@ -179,6 +179,8 @@ void sensorManager::publishDetection()
std
::
cout
<<
"BEV objects: "
<<
vGrid
->
vInsObjs
.
size
()
<<
std
::
endl
;
std
::
cout
<<
"BEV objects: "
<<
vGrid
->
vInsObjs
.
size
()
<<
std
::
endl
;
waytous_perception_msgs
::
ObjectArray
obFrame
;
waytous_perception_msgs
::
ObjectArray
obFrame
;
waytous_perception_msgs
::
ObjectTrackArray
obTrackFrame
;
int8_t
obj_id
=
0
;
int8_t
obj_id
=
0
;
for
(
auto
&
obj
:
vGrid
->
vInsObjs
)
for
(
auto
&
obj
:
vGrid
->
vInsObjs
)
{
{
...
@@ -187,10 +189,14 @@ void sensorManager::publishDetection()
...
@@ -187,10 +189,14 @@ void sensorManager::publishDetection()
continue
;
continue
;
}
}
waytous_perception_msgs
::
Object
ob
;
waytous_perception_msgs
::
Object
ob
;
waytous_perception_msgs
::
ObjectTrack
obTrack
;
ob
.
sensor_type
=
waytous_perception_msgs
::
Object
::
SENSOR_CAMERA
;
ob
.
sensor_type
=
waytous_perception_msgs
::
Object
::
SENSOR_CAMERA
;
obTrack
.
msgname
=
"camera"
;
//int8 id = 1;
//int8 id = 1;
ob
.
id
=
obj_id
++
;
ob
.
id
=
obj_id
++
;
obTrack
.
track_id
=
ob
.
id
;
//int8 property = 2;
//int8 property = 2;
...
@@ -227,6 +233,10 @@ void sensorManager::publishDetection()
...
@@ -227,6 +233,10 @@ void sensorManager::publishDetection()
ob
.
dimensions
.
x
=
(
obj
.
rrc
.
size
.
width
*
BEV_GRID_RESOLUTION
);
ob
.
dimensions
.
x
=
(
obj
.
rrc
.
size
.
width
*
BEV_GRID_RESOLUTION
);
ob
.
dimensions
.
y
=
(
obj
.
rrc
.
size
.
height
*
BEV_GRID_RESOLUTION
);
ob
.
dimensions
.
y
=
(
obj
.
rrc
.
size
.
height
*
BEV_GRID_RESOLUTION
);
ob
.
dimensions
.
z
=
1
;
ob
.
dimensions
.
z
=
1
;
// jsk_recognition_msgs/BoundingBox
obTrack
.
bounding_box
.
pose
=
ob
.
pose
;
obTrack
.
bounding_box
.
dimensions
=
ob
.
dimensions
;
//geometry_msgs/Polygon convex_hull = 7
//geometry_msgs/Polygon convex_hull = 7
cv
::
Point2f
vertices
[
4
];
cv
::
Point2f
vertices
[
4
];
...
@@ -257,6 +267,7 @@ void sensorManager::publishDetection()
...
@@ -257,6 +267,7 @@ void sensorManager::publishDetection()
// int8 label_type = 9
// int8 label_type = 9
ob
.
label_type
=
(
name2type
.
find
(
obj
.
names
)
==
name2type
.
end
()
?
Perception_Default_Classification
:
name2type
[
obj
.
names
]);
ob
.
label_type
=
(
name2type
.
find
(
obj
.
names
)
==
name2type
.
end
()
?
Perception_Default_Classification
:
name2type
[
obj
.
names
]);
obTrack
.
track_type
=
(
name2type
.
find
(
obj
.
names
)
==
name2type
.
end
()
?
Perception_Default_Classification
:
name2type
[
obj
.
names
]);
//float32[] type_probs = 10
//float32[] type_probs = 10
// std::vector<float> probs(waytous_perception_msgs::Object::TYPE_UNKNOWN_STATIC + 1, 0); // main-type length
// std::vector<float> probs(waytous_perception_msgs::Object::TYPE_UNKNOWN_STATIC + 1, 0); // main-type length
...
@@ -280,8 +291,9 @@ void sensorManager::publishDetection()
...
@@ -280,8 +291,9 @@ void sensorManager::publishDetection()
// geometry_msgs/Vector3[] trajectory # optional
// geometry_msgs/Vector3[] trajectory # optional
// FleetObject fleet_object # optional
// FleetObject fleet_object # optional
obFrame
.
foreground_objects
.
emplace_back
(
ob
);
obFrame
.
foreground_objects
.
emplace_back
(
ob
);
obTrackFrame
.
foreground_objects
.
emplace_back
(
obTrack
);
}
}
obj_publisher_
.
publish
(
ob
Frame
);
obj_publisher_
.
publish
(
ob
TrackFrame
);
// obFrame or obTrackFrame
std
::
cout
<<
" onRun : "
<<
double
(
clock
()
-
start_
)
/
CLOCKS_PER_SEC
<<
"s. "
<<
"Detected Objects: "
std
::
cout
<<
" onRun : "
<<
double
(
clock
()
-
start_
)
/
CLOCKS_PER_SEC
<<
"s. "
<<
"Detected Objects: "
<<
obFrame
.
foreground_objects
.
size
()
<<
std
::
endl
;
//输出时间(单位:s)
<<
obFrame
.
foreground_objects
.
size
()
<<
std
::
endl
;
//输出时间(单位:s)
...
...
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