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
b4d112e0
Commit
b4d112e0
authored
Aug 11, 2022
by
oscar
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
update
parent
27f46add
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
18 additions
and
4 deletions
+18
-4
BaseTrack.cpp
BaseTracker/BaseTrack.cpp
+5
-0
BaseTrack.h
BaseTracker/BaseTrack.h
+1
-0
TrackingObj.cpp
Tracking/TrackingObj.cpp
+2
-0
TrackingObj.h
Tracking/TrackingObj.h
+1
-0
TrackingRos2.cpp
ros2/TrackingRos2.cpp
+9
-4
No files found.
BaseTracker/BaseTrack.cpp
View file @
b4d112e0
...
...
@@ -103,6 +103,11 @@ bool BaseTrack::IsValid()
{
return
m_update_count
>=
m_updateValidCount
;
}
bool
BaseTrack
::
IsValid
(
int
&
updateNum
)
{
updateNum
=
m_update_count
;
return
m_update_count
>=
m_updateValidCount
;
}
int
BaseTrack
::
GetIouData
(
std
::
vector
<
float
>&
data
,
int
&
obj_type
)
{
if
(
kf_
==
nullptr
||
m_num_obs
>
m_num_states
)
...
...
BaseTracker/BaseTrack.h
View file @
b4d112e0
...
...
@@ -29,6 +29,7 @@ public:
virtual
float
GetProb
()
const
;
virtual
bool
IsLost
();
//数据是否丢失,如果不更新就会丢失
virtual
bool
IsValid
();
//数据是否有效
virtual
bool
IsValid
(
int
&
updateNum
);
//数据是否有效,返回更新次数
virtual
int
GetIouData
(
std
::
vector
<
float
>&
data
,
int
&
obj_type
);
...
...
Tracking/TrackingObj.cpp
View file @
b4d112e0
...
...
@@ -46,6 +46,8 @@ namespace juefx_tracking
std
::
vector
<
float
>
values
;
values
.
push_back
(
matrix_angle_r_value
);
m_tracker
.
SetValues
(
values
);
if
(
m_config
[
"update_invalid_num"
])
m_update_invalid_num
=
m_config
[
"update_invalid_num"
].
as
<
int32_t
>
();
if
(
config
[
"TRANS"
])
m_trans
=
config
[
"TRANS"
].
as
<
std
::
vector
<
std
::
vector
<
double
>>>
();
...
...
Tracking/TrackingObj.h
View file @
b4d112e0
...
...
@@ -48,6 +48,7 @@ namespace juefx_tracking
YAML
::
Node
m_config
;
TrackingProcessCallback
m_cb
=
nullptr
;
int
m_update_invalid_num
=
10
;
//开始产生的时候速度不可信的帧数
};
...
...
ros2/TrackingRos2.cpp
View file @
b4d112e0
...
...
@@ -188,6 +188,7 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
int
is_need_send
=
0
;
//是否需要发送
int
camera_id
=
0
;
int
tracking_id
=
0
;
int
updateNum
=
0
;
// if (updateId.find(iter.first) != updateId.end()) {
// input_obj = objsPtr->feature_objects
// [updateId[iter.first]];
...
...
@@ -261,7 +262,7 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
}
}
std
::
vector
<
float
>
data
;
if
(
iter
.
second
->
IsValid
()
&&
if
(
iter
.
second
->
IsValid
(
updateNum
)
&&
iter
.
second
->
GetStateData
(
data
)
==
0
)
//初始obj更新跟踪的推理结果
{
is_need_send
=
1
;
//需要发送
...
...
@@ -301,7 +302,7 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
if
(
iter
.
second
->
m_obj
&&
iter
.
second
->
m_obj
->
obj
)
obj
=
*
(
iter
.
second
->
m_obj
->
obj
);
std
::
vector
<
float
>
data
;
if
(
iter
.
second
->
IsValid
()
&&
if
(
iter
.
second
->
IsValid
(
updateNum
)
&&
iter
.
second
->
GetStateData
(
data
)
==
0
)
//跟踪链有效且获取到预测结果,初始obj更新跟踪的推理结果
{
...
...
@@ -333,7 +334,10 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
}
while
(
orient
.
y
<
-
_PI_
)
{
orient
.
y
+=
_PI_
*
2
;
}
}
int
cof
=
obj
.
existence_probability
;
if
(
updateNum
!=
0
&&
updateNum
<=
m_tracking
.
m_update_invalid_num
)
//
obj
.
existence_probability
=
0.0
f
;
geometry_msgs
::
msg
::
Vector3
&
linear
=
obj
.
kinematics
.
twist_with_covariance
.
twist
.
linear
;
linear
.
x
*=
10
;
...
...
@@ -409,7 +413,8 @@ void TrackingRos2::TrackingPorcess(objTrackListPtr objsPtr) {
markerText
.
color
.
a
=
1.0
;
char
str
[
512
]
=
{};
sprintf
(
str
,
"%d:%.2f"
,
iter
.
first
,
linear
.
x
);
// sprintf(str, "%.2f:%d:%.2f",obj.existence_probability,obj.classification[0].label,poss.x);
// sprintf(str, "%d:%d",iter.first,obj.classification[0].label);
// sprintf(str, "%.2f:%d:%.2f:%.2f",cof,obj.classification[0].label,poss.x,linear.x);
markerText
.
text
=
str
;
makerTextArray
.
markers
.
emplace_back
(
markerText
);
sendObjs
.
objects
.
emplace_back
(
obj
);
...
...
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