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
6eef567d
Commit
6eef567d
authored
Dec 20, 2021
by
oscar
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
提交角度修改
parent
52b186b8
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
2 additions
and
2 deletions
+2
-2
TrackingRos.cpp
TrackingRos.cpp
+2
-2
No files found.
TrackingRos.cpp
View file @
6eef567d
...
...
@@ -270,7 +270,7 @@ void TrackingRos::ThreadTrackingProcess()
//SDK_LOG(SDK_INFO, "lat = %.10f, lon = %.10f", obj.Lat, obj.Long);
}
}
//修正rot_y值
//修正rot_y值
,变为角度
to360
(
obj
.
rot_y
,
m_lidar_x_angle
);
jsk_recognition_msgs
::
BoundingBox
box
=
{};
...
...
@@ -283,7 +283,7 @@ void TrackingRos::ThreadTrackingProcess()
box
.
pose
.
position
.
x
=
obj
.
x
;
box
.
pose
.
position
.
y
=
obj
.
y
;
box
.
pose
.
position
.
z
=
obj
.
z
;
Eigen
::
AngleAxisd
V3
(
obj
.
rot_y
,
Eigen
::
Vector3d
(
0
,
0
,
1
));
Eigen
::
AngleAxisd
V3
(
obj
.
rot_y
/
180
*
3.14159265
,
Eigen
::
Vector3d
(
0
,
0
,
1
));
Eigen
::
Quaterniond
R_quat
(
V3
);
box
.
pose
.
orientation
.
x
=
R_quat
.
x
();
box
.
pose
.
orientation
.
y
=
R_quat
.
y
();
...
...
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