Skip to content
Projects
Groups
Snippets
Help
Loading...
Sign in / Register
Toggle navigation
J
jfx_kalman_filter_src
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
Packages
Packages
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
oscar
jfx_kalman_filter_src
Commits
b54c5360
Commit
b54c5360
authored
Jan 12, 2022
by
oscar
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
提交更新
parent
abc40a86
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
7 additions
and
7 deletions
+7
-7
TrackingRosEx.cpp
TrackingRosEx.cpp
+7
-7
No files found.
TrackingRosEx.cpp
View file @
b54c5360
...
...
@@ -376,7 +376,7 @@ void TrackingRos::TrackingCallBackFunc(const jfx_common_msgs::det_tracking_array
}
//m_objsQueue.push(objsPtr);
m_pubCloud
.
publish
(
msg
->
cloud
);
//
m_pubCloud.publish(msg->cloud);
}
...
...
@@ -621,7 +621,7 @@ void TrackingRos::ThreadTrackingProcess()
//SDK_LOG(SDK_INFO, "run before size = %d, after size = %d,",objsPtr->array.size(), trackers.size());
jfx_common_msgs
::
det_tracking_array
sendObjs
=
{};
jsk_recognition_msgs
::
BoundingBoxArray
sendBoxes
=
{};
sendBoxes
.
header
.
frame_id
=
"
Pandar64
"
;
sendBoxes
.
header
.
frame_id
=
"
/rslidar
"
;
for
(
auto
&
iter
:
trackers
)
{
jfx_common_msgs
::
det_tracking
obj
=
{};
...
...
@@ -702,7 +702,7 @@ void TrackingRos::ThreadTrackingProcess()
{
obj
.
rot_y
+=
_PI_
*
2
;
}
//
float rot_y_angle = obj.rot_y;
float
rot_y_angle
=
obj
.
rot_y
;
//obj.rot_y = to360(obj.rot_y, m_lidar_x_angle);
//SDK_LOG(SDK_INFO, "rot_y_angle = %f, rot_y = %f", rot_y_angle, obj.rot_y);
std
::
vector
<
float
>
predict
;
...
...
@@ -722,9 +722,9 @@ void TrackingRos::ThreadTrackingProcess()
}
jsk_recognition_msgs
::
BoundingBox
box
=
{};
box
.
label
=
obj
.
obj_id
;
box
.
label
=
obj
.
type
;
box
.
value
=
obj
.
obj_id
;
box
.
header
.
frame_id
=
"
Pandar64
"
;
box
.
header
.
frame_id
=
"
/rslidar
"
;
box
.
dimensions
.
x
=
obj
.
l
;
box
.
dimensions
.
y
=
obj
.
w
;
box
.
dimensions
.
z
=
obj
.
h
;
...
...
@@ -736,7 +736,7 @@ void TrackingRos::ThreadTrackingProcess()
box
.
pose
.
orientation
.
x
=
R_quat
.
x
();
box
.
pose
.
orientation
.
y
=
R_quat
.
y
();
box
.
pose
.
orientation
.
z
=
R_quat
.
z
();
box
.
pose
.
orientation
.
w
=
R_quat
.
w
()
;
box
.
pose
.
orientation
.
w
=
rot_y_angle
;
sendBoxes
.
boxes
.
emplace_back
(
box
);
sendObjs
.
array
.
emplace_back
(
obj
);
}
...
...
@@ -744,7 +744,7 @@ void TrackingRos::ThreadTrackingProcess()
//sendObjs.cloud = objsPtr->cloud;
//SDK_LOG(SDK_INFO, "calculate objs size = %d", sendObjs.array.size());
m_pub
.
publish
(
sendObjs
);
//
m_pub.publish(sendObjs);
m_pubBoundingBoxes
.
publish
(
sendBoxes
);
#ifdef _USING_NSIGHT_
nvtxRangePop
();
...
...
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