Skip to content
Projects
Groups
Snippets
Help
Loading...
Sign in / Register
Toggle navigation
J
jfx_node_ros
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_node_ros
Commits
d2311b6d
Commit
d2311b6d
authored
May 16, 2023
by
oscar
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
上传mota的计算指标的逻辑
parent
d6f5d7a2
Show whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
666 additions
and
15 deletions
+666
-15
CMakeLists.txt
MOTA/CMakeLists.txt
+71
-0
main.cpp
MOTA/main.cpp
+187
-0
jfx_node_ros.launch
launch/jfx_node_ros.launch
+18
-2
SendRosMsg.cpp
src/SendRosMsg.cpp
+296
-10
SendRosMsg.hpp
src/SendRosMsg.hpp
+2
-0
main.cpp
src/main.cpp
+92
-3
No files found.
MOTA/CMakeLists.txt
0 → 100644
View file @
d2311b6d
cmake_minimum_required
(
VERSION 3.0.2
)
project
(
mota
)
set
(
CMAKE_CXX_FLAGS
"
${
CMAKE_CXX_FLAGS
}
-fprofile-arcs -ftest-coverage -pthread"
)
#SET(CMAKE_BUILD_TYPE "Debug")
SET
(
CMAKE_BUILD_TYPE
"Release"
)
# set(CMAKE_POSITION_INDEPENDENT_CODE TRUE)
# include_directories(./)
# include_directories(./include)
# include_directories(./src/)
# include_directories(./src/DeInflate)
# include_directories(./src/Endecryption)
add_executable
(
test main.cpp
)
# target_link_libraries(test
# crypto
# ssl
# z
# )
# add_executable(test1 test1.cpp)
# target_link_libraries(test1
# crypto
# ssl
# z
# )
# add_executable(test3 test3.cpp)
# target_link_libraries(test3
# crypto
# ssl
# z
# )
# add_executable(main
# main.cpp
# src/DeInflate/DeInflate.cpp
# )
# target_link_libraries(main
# crypto
# ssl
# z
# )
# add_library(generateLicense SHARED
# src/DeInflate/DeInflate.cpp
# src/GenerateLicense.cpp
# src/Endecryption/EncryptWithRsa.cpp
# src/Endecryption/Endecrypt.cpp
# )
# target_link_libraries(generateLicense
# crypto.a
# ssl.a
# /usr/local/lib/libz.a
# )
# add_executable(generate
# Generate.cpp
# # src/CheckLicense.cpp
# # src/Endecryption/DecryptWithRsa.cpp
# )
# target_link_libraries(generate
# # crypto
# # ssl
# # z
# generateLicense
# dl
# )
MOTA/main.cpp
0 → 100644
View file @
d2311b6d
#include <iostream>
#include <fstream>
#include <sstream>
#include <vector>
#include <map>
#include <cmath>
using
namespace
std
;
struct
BoundingBox
{
float
x
;
float
y
;
float
z
;
float
length
;
float
width
;
float
height
;
float
orientation
;
};
struct
Object
{
int
object_id
;
int
frame_id
;
BoundingBox
bbox
;
float
confidence
;
int
type
;
string
class_name
;
};
// 读取CSV格式的文件
vector
<
Object
>
read_csv_file
(
const
string
&
filename
)
{
vector
<
Object
>
data
;
ifstream
file
(
filename
);
string
line
;
while
(
getline
(
file
,
line
))
{
if
(
line
.
empty
())
{
continue
;
}
stringstream
ss
(
line
);
string
field
;
vector
<
string
>
fields
;
while
(
getline
(
ss
,
field
,
','
))
{
fields
.
push_back
(
field
);
}
Object
obj
;
obj
.
object_id
=
stoi
(
fields
[
0
]);
obj
.
frame_id
=
stoi
(
fields
[
1
]);
obj
.
bbox
.
x
=
stof
(
fields
[
2
]);
obj
.
bbox
.
y
=
stof
(
fields
[
3
]);
obj
.
bbox
.
z
=
stof
(
fields
[
4
]);
obj
.
bbox
.
length
=
stof
(
fields
[
5
]);
obj
.
bbox
.
width
=
stof
(
fields
[
6
]);
obj
.
bbox
.
height
=
stof
(
fields
[
7
]);
obj
.
bbox
.
orientation
=
stof
(
fields
[
8
]);
obj
.
confidence
=
stof
(
fields
[
9
]);
obj
.
type
=
stoi
(
fields
[
10
]);
obj
.
class_name
=
fields
[
11
];
data
.
push_back
(
obj
);
}
return
data
;
}
// 计算IoU
float
calculate_iou_3d
(
const
BoundingBox
&
bbox1
,
const
BoundingBox
&
bbox2
)
{
float
dx
=
abs
(
bbox1
.
x
-
bbox2
.
x
);
float
dy
=
abs
(
bbox1
.
y
-
bbox2
.
y
);
float
dz
=
abs
(
bbox1
.
z
-
bbox2
.
z
);
float
delta_l
=
abs
(
bbox1
.
length
-
bbox2
.
length
);
float
delta_w
=
abs
(
bbox1
.
width
-
bbox2
.
width
);
float
delta_h
=
abs
(
bbox1
.
height
-
bbox2
.
height
);
float
delta_o
=
abs
(
bbox1
.
orientation
-
bbox2
.
orientation
);
float
delta_xyz
=
sqrt
(
dx
*
dx
+
dy
*
dy
+
dz
*
dz
);
float
delta_dim
=
sqrt
(
delta_l
*
delta_l
+
delta_w
*
delta_w
+
delta_h
*
delta_h
);
float
delta_orien
=
delta_o
;
float
iou_xyz
=
1.0
f
-
delta_xyz
/
(
bbox1
.
length
+
bbox1
.
width
+
bbox1
.
height
+
bbox2
.
length
+
bbox2
.
width
+
bbox2
.
height
);
float
iou_dim
=
1.0
f
-
delta_dim
/
(
bbox1
.
length
+
bbox1
.
width
+
bbox1
.
height
+
bbox2
.
length
+
bbox2
.
width
+
bbox2
.
height
);
float
iou_orien
=
1.0
f
-
delta_orien
/
M_PI
;
float
iou
=
iou_xyz
*
iou_dim
*
iou_orien
;
return
iou
;
}
// 计算匹配分数
map
<
int
,
map
<
int
,
map
<
int
,
float
>>>
calculate_match_score_3d
(
const
vector
<
Object
>&
tracking_data
,
const
vector
<
Object
>&
gt_data
,
float
iou_threshold
)
{
map
<
int
,
map
<
int
,
map
<
int
,
float
>>>
match_score
;
for
(
const
auto
&
obj1
:
tracking_data
)
{
for
(
const
auto
&
obj2
:
gt_data
)
{
if
(
obj1
.
frame_id
==
obj2
.
frame_id
)
{
float
iou
=
calculate_iou_3d
(
obj1
.
bbox
,
obj2
.
bbox
);
if
(
iou
>
iou_threshold
)
{
match_score
[
obj1
.
frame_id
][
obj1
.
object_id
][
obj2
.
object_id
]
=
iou
;
}
}
}
}
return
match_score
;
}
// 确定真实值和跟踪结果之间的匹配关系
map
<
int
,
map
<
int
,
int
>>
get_matches
(
const
map
<
int
,
map
<
int
,
map
<
int
,
float
>>>&
match_score
)
{
map
<
int
,
map
<
int
,
int
>>
matches
;
for
(
const
auto
&
frame_pair
:
match_score
)
{
matches
[
frame_pair
.
first
];
map
<
int
,
int
>
used_objects
;
map
<
int
,
int
>
used_gt_objects
;
for
(
const
auto
&
object_pair
:
frame_pair
.
second
)
{
int
object_id
=
object_pair
.
first
;
int
max_gt_object_id
=
-
1
;
float
max_iou
=
0
;
for
(
const
auto
&
gt_object_pair
:
object_pair
.
second
)
{
int
gt_object_id
=
gt_object_pair
.
first
;
float
iou
=
gt_object_pair
.
second
;
if
(
iou
>
max_iou
&&
used_gt_objects
.
count
(
gt_object_id
)
==
0
)
{
max_iou
=
iou
;
max_gt_object_id
=
gt_object_id
;
}
}
if
(
max_gt_object_id
!=
-
1
)
{
matches
[
frame_pair
.
first
][
object_id
]
=
max_gt_object_id
;
used_objects
[
object_id
]
=
1
;
used_gt_objects
[
max_gt_object_id
]
=
1
;
}
}
for
(
const
auto
&
object_pair
:
frame_pair
.
second
)
{
int
object_id
=
object_pair
.
first
;
if
(
used_objects
.
count
(
object_id
)
==
0
)
{
matches
[
frame_pair
.
first
][
object_id
]
=
-
1
;
}
}
for
(
const
auto
&
gt_object_pair
:
frame_pair
.
second
.
begin
()
->
second
)
{
int
gt_object_id
=
gt_object_pair
.
first
;
if
(
used_gt_objects
.
count
(
gt_object_id
)
==
0
)
{
matches
[
frame_pair
.
first
][
-
1
]
=
gt_object_id
;
}
}
}
return
matches
;
}
// 计算MOTA指标
float
calculate_mota_3d
(
const
vector
<
Object
>&
tracking_data
,
const
vector
<
Object
>&
gt_data
,
float
iou_threshold
)
{
auto
match_score
=
calculate_match_score_3d
(
tracking_data
,
gt_data
,
iou_threshold
);
auto
matches
=
get_matches
(
match_score
);
int
num_misses
=
0
;
int
num_false_positives
=
0
;
int
num_switches
=
0
;
int
num_objects
=
0
;
for
(
const
auto
&
frame_pair
:
matches
)
{
for
(
const
auto
&
object_pair
:
frame_pair
.
second
)
{
int
object_id
=
object_pair
.
first
;
int
gt_object_id
=
object_pair
.
second
;
if
(
object_id
==
-
1
)
{
num_misses
++
;
}
else
if
(
gt_object_id
==
-
1
)
{
num_false_positives
++
;
}
else
{
num_objects
++
;
if
(
match_score
[
frame_pair
.
first
][
object_id
][
gt_object_id
]
<
iou_threshold
)
{
num_switches
++
;
}
}
}
}
float
mota
=
1.0
f
-
(
float
)(
num_misses
+
num_false_positives
+
num_switches
)
/
num_objects
;
return
mota
;
}
int
main
(
int
argc
,
char
**
argv
)
{
std
::
string
tracking_csv
=
"tracking_data.csv"
;
std
::
string
gt_csv
=
"gt_data.csv"
;
if
(
argc
==
3
)
{
tracking_csv
=
argv
[
1
];
gt_csv
=
argv
[
2
];
}
// 读取跟踪结果和真值
vector
<
Object
>
tracking_data
=
read_csv_file
(
tracking_csv
);
vector
<
Object
>
gt_data
=
read_csv_file
(
gt_csv
);
// 计算MOTA指标
float
iou_threshold
=
0.5
;
float
mota
=
calculate_mota_3d
(
tracking_data
,
gt_data
,
iou_threshold
);
cout
<<
"MOTA = "
<<
mota
<<
endl
;
return
0
;
}
\ No newline at end of file
launch/jfx_node_ros.launch
View file @
d2311b6d
<launch>
<arg name="parampath" default="$(find jfx_node_ros)/config/params.yaml"/>
<arg name="run_mode" default="
1
"/>
<arg name="run_mode" default="
2
"/>
<arg name="originDataPath" default="/media/sf_originData/data"/>
<arg name="gps_load_file" default="/media/sf_originData/102022041610.nav/102022041610_traj.txt"/>
<arg name="outPutSaveDir" default="/media/sf_originData/detect_data/"/>
<arg name="playDetectTxt" default="/media/sf_originData/detect_data/detect_gps_
7.txt
"/>
<arg name="playDetectTxt" default="/media/sf_originData/detect_data/detect_gps_
31.csv
"/>
<arg name="pcdFileFolder" default="/media/sf_pcd_image/mesh"/>
<arg name="image0FileFolder" default="/media/sf_pcd_image/102022041610/image0"/>
<arg name="image1FileFolder" default="/media/sf_pcd_image/102022041610/image1"/>
<arg name="save_data_folder" default="/media/sf_originData/save_data"/>
<arg name="start_timestamp" default="/1650066200187"/>
<arg name="finish_timestamp" default="/1650066240187"/>
<arg name="send_pcd" default="1"/>
<arg name="send_image" default="1"/>
<arg name="play_save_gps_csv" default="/media/sf_originData/save_data/20230515-154612/detec_gps.csv"/>
<arg name="play_save_detect_folder" default="/media/sf_originData/save_data/20230515-154612/detect"/>
<arg name="play_save_pcd_folder" default="/media/sf_originData/save_data/20230515-154612/pcd"/>
<arg name="play_save_image0_folder" default="/media/sf_originData/save_data/20230515-154612/image0"/>
<arg name="play_save_image1_folder" default="/media/sf_originData/save_data/20230515-154612/image1"/>
<node pkg="jfx_node_ros" type="jfx_node_ros" name="jfx_node_ros" output="screen" >
<param name="parampath" value="$(arg parampath)" />
<param name="run_mode" value="$(arg run_mode)" />
...
...
@@ -20,7 +28,15 @@
<param name="pcdFileFolder" value="$(arg pcdFileFolder)" />
<param name="image0FileFolder" value="$(arg image0FileFolder)" />
<param name="image1FileFolder" value="$(arg image1FileFolder)" />
<param name="save_data_folder" value="$(arg save_data_folder)" />
<param name="start_timestamp" value="$(arg start_timestamp)" />
<param name="finish_timestamp" value="$(arg finish_timestamp)" />
<param name="send_pcd" value="$(arg send_pcd)" />
<param name="send_image" value="$(arg send_image)" />
<param name="play_save_gps_csv" value="$(arg play_save_gps_csv)" />
<param name="play_save_detect_folder" value="$(arg play_save_detect_folder)" />
<param name="play_save_pcd_folder" value="$(arg play_save_pcd_folder)" />
<param name="play_save_image0_folder" value="$(arg play_save_image0_folder)" />
<param name="play_save_image1_folder" value="$(arg play_save_image1_folder)" />
</node>
</launch>
src/SendRosMsg.cpp
View file @
d2311b6d
...
...
@@ -26,6 +26,77 @@ uint64_t GetCurTime()
return
ttt
;
}
int32_t
OpendirAndMkdir
(
const
char
*
pathname
)
{
int
ret
=
0
;
DIR
*
mydir
=
NULL
;
if
((
mydir
=
opendir
(
pathname
))
==
NULL
)
//
{
ret
=
mkdir
(
pathname
,
0755
);
if
(
ret
!=
0
)
return
-
1
;
printf
(
"%s created sucess!/n"
,
pathname
);
}
else
{
printf
(
"%s exist!/n"
,
pathname
);
}
return
ret
;
}
int
copyFile
(
std
::
string
&
src
,
std
::
string
&
dst
)
{
// Open the source file for reading
std
::
ifstream
source_file
(
src
,
std
::
ios
::
binary
);
if
(
!
source_file
)
{
std
::
cerr
<<
"Error: Could not open source file "
<<
src
<<
std
::
endl
;
return
1
;
}
// Open the destination file for writing
std
::
ofstream
dest_file
(
dst
,
std
::
ios
::
binary
);
if
(
!
dest_file
)
{
std
::
cerr
<<
"Error: Could not open destination file "
<<
dst
<<
std
::
endl
;
return
1
;
}
// Read from the source file and write to the destination file
char
buffer
[
1024
];
while
(
source_file
.
read
(
buffer
,
sizeof
(
buffer
)))
{
dest_file
.
write
(
buffer
,
source_file
.
gcount
());
}
// Check for errors during the copy process
if
(
source_file
.
bad
())
{
std
::
cerr
<<
"Error: Failed to read from source file "
<<
src
<<
std
::
endl
;
return
1
;
}
if
(
dest_file
.
bad
())
{
std
::
cerr
<<
"Error: Failed to write to destination file "
<<
dst
<<
std
::
endl
;
return
1
;
}
// Close the files
source_file
.
close
();
dest_file
.
close
();
std
::
cout
<<
"File copy completed successfully."
<<
std
::
endl
;
return
0
;
}
int
copyFile2
(
std
::
string
&
src
,
std
::
string
&
dst
)
{
std
::
ifstream
srcFile
(
src
,
std
::
ios
::
binary
);
std
::
ofstream
dstFile
(
dst
,
std
::
ios
::
binary
);
dstFile
<<
srcFile
.
rdbuf
();
srcFile
.
close
();
dstFile
.
close
();
return
0
;
}
void
rotate_pointcloud
(
pcl
::
PointCloud
<
pcl
::
PointXYZ
>::
Ptr
cloud_in
,
pcl
::
PointCloud
<
pcl
::
PointXYZ
>::
Ptr
cloud_out
)
{
// 顺时针旋转90度
...
...
@@ -55,17 +126,17 @@ int LoadFileSendRosMsg::Play(ros::NodeHandle& nh)
image_transport
::
ImageTransport
it1
(
nh
);
image_transport
::
Publisher
pubImage1
=
it1
.
advertise
(
"/image1"
,
1
);
std
::
string
loadFile
=
"/media/sf_originData/
detect_data/detect_gps_40.txt
"
;
nh
.
param
<
std
::
string
>
(
"play
DetectTxt"
,
loadFile
,
"/media/sf_originData/detect_data/detect_gps_40.txt
"
);
std
::
string
loadFile
=
"/media/sf_originData/
save_data/20230515-151053/detec_gps.csv
"
;
nh
.
param
<
std
::
string
>
(
"play
_save_gps_csv"
,
loadFile
,
"/media/sf_originData/save_data/20230515-151053/detec_gps.csv
"
);
std
::
string
detectFolder
=
"/media/sf_originData/
data
"
;
nh
.
param
<
std
::
string
>
(
"
originDataPath"
,
detectFolder
,
"/media/sf_originData/data
"
);
std
::
string
pcdFolder
=
"/media/sf_
pcd_image/mesh
"
;
nh
.
param
<
std
::
string
>
(
"p
cdFileFolder"
,
pcdFolder
,
"/media/sf_pcd_image/mesh
"
);
std
::
string
image0Folder
=
"/media/sf_
pcd_image/102022041610
/image0"
;
nh
.
param
<
std
::
string
>
(
"
image0FileFolder"
,
image0Folder
,
"/media/sf_pcd_image/102022041610
/image0"
);
std
::
string
image1Folder
=
"/media/sf_
pcd_image/102022041610
/image1"
;
nh
.
param
<
std
::
string
>
(
"
image1FileFolder"
,
image1Folder
,
"/media/sf_pcd_image/102022041610
/image1"
);
std
::
string
detectFolder
=
"/media/sf_originData/
save_data/20230515-151053/detect
"
;
nh
.
param
<
std
::
string
>
(
"
play_save_detect_folder"
,
detectFolder
,
"/media/sf_originData/save_data/20230515-151053/detect
"
);
std
::
string
pcdFolder
=
"/media/sf_
originData/save_data/20230515-151053/pcd
"
;
nh
.
param
<
std
::
string
>
(
"p
lay_save_pcd_folder"
,
pcdFolder
,
"/media/sf_originData/save_data/20230515-151053/pcd
"
);
std
::
string
image0Folder
=
"/media/sf_
originData/save_data/20230515-151053
/image0"
;
nh
.
param
<
std
::
string
>
(
"
play_save_image0_folder"
,
image0Folder
,
"/media/sf_originData/save_data/20230515-151053
/image0"
);
std
::
string
image1Folder
=
"/media/sf_
originData/save_data/20230515-151053
/image1"
;
nh
.
param
<
std
::
string
>
(
"
play_save_image1_folder"
,
image1Folder
,
"/media/sf_originData/save_data/20230515-151053
/image1"
);
int
send_pcd
=
0
;
int
send_image
=
0
;
...
...
@@ -186,6 +257,14 @@ int LoadFileSendRosMsg::Play(ros::NodeHandle& nh)
det_info
.
w
=
std
::
stof
(
_values
[
4
]);
det_info
.
h
=
std
::
stof
(
_values
[
5
]);
det_info
.
rot_y
=
rot
;
if
(
det_info
.
type
==
1
)
det_info
.
name
=
"car"
;
else
if
(
det_info
.
type
==
2
)
det_info
.
name
=
"truck"
;
else
if
(
det_info
.
type
==
3
)
det_info
.
name
=
"bus"
;
else
det_info
.
name
=
"vechile"
;
det_array
.
array
.
emplace_back
(
det_info
);
jsk_recognition_msgs
::
BoundingBox
box
=
{};
...
...
@@ -307,3 +386,209 @@ int LoadFileSendRosMsg::Play(ros::NodeHandle& nh)
printf
(
"pub finish
\n
"
);
return
0
;
}
int
LoadFileSendRosMsg
::
SaveFiles
(
ros
::
NodeHandle
&
nh
)
{
std
::
string
loadFile
=
"/media/sf_originData/detect_data/detect_gps_40.txt"
;
nh
.
param
<
std
::
string
>
(
"playDetectTxt"
,
loadFile
,
"/media/sf_originData/detect_data/detect_gps_40.txt"
);
std
::
string
detectFolder
=
"/media/sf_originData/data"
;
nh
.
param
<
std
::
string
>
(
"originDataPath"
,
detectFolder
,
"/media/sf_originData/data"
);
std
::
string
pcdFolder
=
"/media/sf_pcd_image/mesh"
;
nh
.
param
<
std
::
string
>
(
"pcdFileFolder"
,
pcdFolder
,
"/media/sf_pcd_image/mesh"
);
std
::
string
image0Folder
=
"/media/sf_pcd_image/102022041610/image0"
;
nh
.
param
<
std
::
string
>
(
"image0FileFolder"
,
image0Folder
,
"/media/sf_pcd_image/102022041610/image0"
);
std
::
string
image1Folder
=
"/media/sf_pcd_image/102022041610/image1"
;
nh
.
param
<
std
::
string
>
(
"image1FileFolder"
,
image1Folder
,
"/media/sf_pcd_image/102022041610/image1"
);
//生成的目录
std
::
string
saveFolder
=
"/media/sf_originData/save_data"
;
nh
.
param
<
std
::
string
>
(
"save_data_folder"
,
saveFolder
,
"/media/sf_originData/save_data"
);
time_t
tt
=
time
(
NULL
);
tm
*
t
=
localtime
(
&
tt
);
char
logName
[
1024
]
=
{};
sprintf
(
logName
,
"%04d%02d%02d-%02d%02d%02d"
,
t
->
tm_year
+
1900
,
t
->
tm_mon
+
1
,
t
->
tm_mday
,
t
->
tm_hour
,
t
->
tm_min
,
t
->
tm_sec
);
std
::
string
newFolder
=
saveFolder
+
"/"
+
std
::
string
(
logName
);
int
ret
=
OpendirAndMkdir
(
newFolder
.
c_str
());
if
(
ret
!=
0
)
return
-
1
;
std
::
string
folder1
=
newFolder
+
"/pcd"
;
//放pcd文件的地方
std
::
string
folder2
=
newFolder
+
"/detect"
;
//放检测物体文件的地方
std
::
string
folder3
=
newFolder
+
"/image0"
;
//放图像0的地方
std
::
string
folder4
=
newFolder
+
"/image1"
;
//放图像1的地方
ret
=
OpendirAndMkdir
(
folder1
.
c_str
());
if
(
ret
!=
0
)
return
-
2
;
ret
=
OpendirAndMkdir
(
folder2
.
c_str
());
if
(
ret
!=
0
)
return
-
3
;
ret
=
OpendirAndMkdir
(
folder3
.
c_str
());
if
(
ret
!=
0
)
return
-
4
;
ret
=
OpendirAndMkdir
(
folder4
.
c_str
());
if
(
ret
!=
0
)
return
-
5
;
std
::
string
csv_gps_file
=
newFolder
+
"/detec_gps.csv"
;
std
::
ofstream
csv_gps
;
csv_gps
.
open
(
csv_gps_file
,
std
::
ios
::
out
);
int64_t
start_timestamp
=
0
;
int64_t
finish_timestamp
=
0
;
std
::
string
start_str
=
"0"
;
std
::
string
finsih_str
=
"0"
;
nh
.
param
<
std
::
string
>
(
"start_timestamp"
,
start_str
,
"1234"
);
nh
.
param
<
std
::
string
>
(
"finish_timestamp"
,
finsih_str
,
"1232"
);
if
(
start_str
.
at
(
0
)
==
'/'
)
start_str
.
erase
(
start_str
.
begin
());
if
(
finsih_str
.
at
(
0
)
==
'/'
)
finsih_str
.
erase
(
finsih_str
.
begin
());
start_timestamp
=
std
::
stoll
(
start_str
);
finish_timestamp
=
std
::
stoll
(
finsih_str
);
std
::
ifstream
gpsFile
;
gpsFile
.
open
(
loadFile
,
std
::
ios
::
in
);
std
::
string
line
;
do
{
std
::
getline
(
gpsFile
,
line
);
if
(
line
.
empty
())
break
;
std
::
vector
<
std
::
string
>
values
;
std
::
stringstream
linestream
(
line
);
std
::
string
cell
;
values
.
clear
();
while
(
std
::
getline
(
linestream
,
cell
,
','
))
{
values
.
push_back
(
cell
);
}
uint64_t
recv_timestamp
=
std
::
stoll
(
values
[
2
]);
if
(
start_timestamp
!=
0
&&
recv_timestamp
<
start_timestamp
)
continue
;
if
(
finish_timestamp
!=
0
&&
recv_timestamp
>
finish_timestamp
)
break
;
if
(
!
values
[
4
].
empty
())
{
std
::
string
detectFile
=
detectFolder
+
"/"
+
values
[
4
];
std
::
string
save_detect_file
=
folder2
+
"/"
+
values
[
3
];
values
[
4
]
=
values
[
3
];
int
rett
=
copyFile2
(
detectFile
,
save_detect_file
);
if
(
rett
!=
0
)
return
-
6
;
}
if
(
!
values
[
5
].
empty
())
{
std
::
string
pcdFile
=
pcdFolder
+
"/"
+
values
[
5
];
size_t
found
=
values
[
3
].
find_last_of
(
'.'
);
std
::
string
ts
=
values
[
3
].
substr
(
0
,
found
);
std
::
string
pcdName
=
ts
+
".pcd"
;
std
::
string
save_pcd_file
=
folder1
+
"/"
+
pcdName
;
values
[
5
]
=
pcdName
;
int
rett
=
copyFile2
(
pcdFile
,
save_pcd_file
);
if
(
rett
!=
0
)
return
-
7
;
}
if
(
!
values
[
6
].
empty
())
{
std
::
string
image0File
=
image0Folder
+
"/"
+
values
[
6
];
std
::
string
save_image0_file
=
folder3
+
"/"
+
values
[
6
];
int
rett
=
copyFile2
(
image0File
,
save_image0_file
);
if
(
rett
!=
0
)
return
-
8
;
}
if
(
!
values
[
7
].
empty
())
{
std
::
string
image1File
=
image1Folder
+
"/"
+
values
[
7
];
std
::
string
save_image1_file
=
folder4
+
"/"
+
values
[
7
];
int
rett
=
copyFile2
(
image1File
,
save_image1_file
);
if
(
rett
!=
0
)
return
-
9
;
}
std
::
stringstream
lineData
;
lineData
<<
std
::
fixed
<<
std
::
setprecision
(
8
);
for
(
int
i
=
0
;
i
<
values
.
size
();
i
++
)
{
if
(
i
!=
0
)
lineData
<<
","
;
lineData
<<
values
[
i
];
}
lineData
<<
std
::
endl
;
std
::
string
str
=
lineData
.
str
();
csv_gps
<<
str
;
printf
(
"save one frame timestamp = %llu
\n
"
,
recv_timestamp
);
}
while
(
1
);
gpsFile
.
close
();
csv_gps
.
close
();
printf
(
"finish SaveFiles
\n
"
);
return
0
;
}
/*
要使用`ofstream`来复制一个文件,可以按照以下步骤:
1. 打开源文件和目标文件,分别使用`ifstream`和`ofstream`类。
2. 读取源文件中的数据并将其写入目标文件中,可以使用`read()`和`write()`函数。
3. 在完成复制后关闭文件。
以下是一个使用`ofstream`来复制文件的示例程序:
```cpp
#include <fstream>
#include <iostream>
#include <string>
int main() {
// Set the source and destination file paths
std::string source_file_path = "/path/to/source/file";
std::string dest_file_path = "/path/to/destination/file";
// Open the source file for reading
std::ifstream source_file(source_file_path, std::ios::binary);
if (!source_file) {
std::cerr << "Error: Could not open source file " << source_file_path << std::endl;
return 1;
}
// Open the destination file for writing
std::ofstream dest_file(dest_file_path, std::ios::binary);
if (!dest_file) {
std::cerr << "Error: Could not open destination file " << dest_file_path << std::endl;
return 1;
}
// Read from the source file and write to the destination file
char buffer[1024];
while (source_file.read(buffer, sizeof(buffer))) {
dest_file.write(buffer, source_file.gcount());
}
// Check for errors during the copy process
if (source_file.bad()) {
std::cerr << "Error: Failed to read from source file " << source_file_path << std::endl;
return 1;
}
if (dest_file.bad()) {
std::cerr << "Error: Failed to write to destination file " << dest_file_path << std::endl;
return 1;
}
// Close the files
source_file.close();
dest_file.close();
std::cout << "File copy completed successfully." << std::endl;
return 0;
}
```
在此示例程序中,首先设置源文件路径和目标文件路径,然后使用`ifstream`和`ofstream`类打开这两个文件。程序使用`read()`和`write()`函数从源文件中读取数据并将其写入目标文件中。在复制过程中,程序检查是否存在任何错误。最后,程序关闭源文件和目标文件,并输出成功消息。
请注意,程序中的`std::ios::binary`标志用于打开二进制文件,以确保在Windows系统上正确复制文件。
*/
\ No newline at end of file
src/SendRosMsg.hpp
View file @
d2311b6d
...
...
@@ -16,6 +16,8 @@ public:
int
Play
(
ros
::
NodeHandle
&
nh
);
int
SaveFiles
(
ros
::
NodeHandle
&
nh
);
ros
::
Publisher
m_pubFusionRes
;
//发送融合后的结果
ros
::
Publisher
m_pubLocalization
;
//发送定位结果
ros
::
Publisher
m_pubBoundingBoxes
;
//发送3D框信息
...
...
src/main.cpp
View file @
d2311b6d
...
...
@@ -19,11 +19,13 @@ struct FileInfo
std
::
string
fileName
;
std
::
string
filePath
;
std
::
string
pcdFile
;
int
carNum
;
};
int
LoadImageList
(
std
::
ifstream
&
file
,
std
::
string
path
,
std
::
vector
<
FileInfo
>&
lists
);
int
FindImageInfoFromTimstamp
(
uint64_t
timestamp
,
std
::
vector
<
FileInfo
>&
lists
,
std
::
string
&
outFile
);
int
SaveFile
(
std
::
ofstream
&
file
,
std
::
string
path
,
FileInfo
&
fileInfo
,
std
::
vector
<
std
::
string
>&
values
,
std
::
vector
<
FileInfo
>&
image0List
,
std
::
vector
<
FileInfo
>&
image1List
);
int
GetCarNumFromFile
(
std
::
string
&
file
);
int
main
(
int
argc
,
char
**
argv
)
{
ros
::
init
(
argc
,
argv
,
"jfx_node_ros"
);
...
...
@@ -73,6 +75,8 @@ int main(int argc, char** argv) {
info
.
pcdFile
=
subDir
+
"/output/"
+
ts
+
".pcd"
;
double
timestamp
=
std
::
stod
(
ts
);
info
.
timestamp
=
timestamp
*
1000
;
std
::
string
carFile
=
directory
+
"/"
+
subFile
;
info
.
carNum
=
GetCarNumFromFile
(
carFile
);
filenames
.
push_back
(
info
);
}
}
...
...
@@ -123,6 +127,8 @@ int main(int argc, char** argv) {
do
{
std
::
getline
(
gpsFile
,
line
);
if
(
line
.
at
(
line
.
size
()
-
1
)
==
'\r'
)
line
.
erase
(
line
.
end
()
-
1
);
if
(
line
.
empty
())
break
;
std
::
vector
<
std
::
string
>
values
;
...
...
@@ -202,6 +208,14 @@ int main(int argc, char** argv) {
ros
::
spin
();
}
else
if
(
run_mode
==
2
)
{
LoadFileSendRosMsg
sendMsg
=
{};
int
ret
=
sendMsg
.
SaveFiles
(
phpriv_nh
);
if
(
ret
!=
0
)
printf
(
"finish error ret = %d"
,
ret
);
ros
::
spin
();
}
return
0
;
...
...
@@ -220,14 +234,14 @@ int SaveFile(std::ofstream& file,std::string path,FileInfo& fileInfo,std::vector
frame
=
1
;
last_timestamp
=
fileInfo
.
timestamp
;
perid_start
=
fileInfo
.
timestamp
;
std
::
string
save_file
=
path
+
"/"
+
"detect_gps_"
+
std
::
to_string
(
perid
)
+
".
txt
"
;
std
::
string
save_file
=
path
+
"/"
+
"detect_gps_"
+
std
::
to_string
(
perid
)
+
".
csv
"
;
file
.
open
(
save_file
,
std
::
ios
::
out
);
printf
(
"save perid = %d begin , file = %s
\n
"
,
perid
,
save_file
.
c_str
());
needPrint
=
1
;
}
else
{
if
(
fileInfo
.
timestamp
-
last_timestamp
<
2
00
)
if
(
fileInfo
.
timestamp
-
last_timestamp
<
5
00
)
{
frame
++
;
}
...
...
@@ -235,9 +249,10 @@ int SaveFile(std::ofstream& file,std::string path,FileInfo& fileInfo,std::vector
{
file
.
close
();
printf
(
"save perid = %d end frame = %d, perid time = %llu
\n
"
,
perid
,
frame
,
last_timestamp
-
perid_start
);
printf
(
"delay time = %llu
\n
"
,
fileInfo
.
timestamp
-
last_timestamp
);
perid
++
;
frame
=
1
;
std
::
string
save_file
=
path
+
"/"
+
"detect_gps_"
+
std
::
to_string
(
perid
)
+
".
txt
"
;
std
::
string
save_file
=
path
+
"/"
+
"detect_gps_"
+
std
::
to_string
(
perid
)
+
".
csv
"
;
file
.
open
(
save_file
,
std
::
ios
::
out
);
printf
(
"save perid = %d begin , file = %s
\n
"
,
perid
,
save_file
.
c_str
());
perid_start
=
fileInfo
.
timestamp
;
...
...
@@ -256,6 +271,7 @@ int SaveFile(std::ofstream& file,std::string path,FileInfo& fileInfo,std::vector
{
lineData
<<
","
<<
iter
;
}
lineData
<<
","
<<
fileInfo
.
carNum
;
lineData
<<
std
::
endl
;
std
::
string
str
=
lineData
.
str
();
if
(
needPrint
==
1
)
...
...
@@ -326,3 +342,75 @@ int FindImageInfoFromTimstamp(uint64_t timestamp,std::vector<FileInfo>& lists,st
else
return
-
1
;
}
int
GetCarNumFromFile
(
std
::
string
&
file
)
{
std
::
ifstream
detFile
;
detFile
.
open
(
file
,
std
::
ios
::
in
);
int
num
=
0
;
do
{
std
::
string
line
;
std
::
getline
(
detFile
,
line
);
if
(
line
.
empty
())
break
;
std
::
vector
<
std
::
string
>
_values
;
std
::
stringstream
_linestream
(
line
);
std
::
string
_cell
;
_values
.
clear
();
while
(
std
::
getline
(
_linestream
,
_cell
,
' '
))
{
_values
.
push_back
(
_cell
);
}
float
score
=
std
::
stof
(
_values
[
7
]);
if
(
score
<
0.4
)
continue
;
num
++
;
}
while
(
1
);
detFile
.
close
();
return
num
;
}
/*
以下是一个C++程序,可以读取给定的CSV文件,并根据每行中的信息创建目录和拷贝文件。你需要将程序中的`csvFilePath`修改为你要读取的CSV文件路径。请注意,此程序假定文件名中没有空格或特殊字符。
```c++
#include <iostream>
#include <fstream>
#include <sstream>
#include <filesystem>
int main() {
const std::string csvFilePath = "/path/to/csv/file.csv"; // 修改为你的CSV文件路径
std::ifstream csvFile(csvFilePath);
if (!csvFile.is_open()) {
std::cerr << "Failed to open file: " << csvFilePath << std::endl;
return 1;
}
std::string line;
while (std::getline(csvFile, line)) {
std::istringstream lineStream(line);
std::string name, path1, path2;
if (std::getline(lineStream, name, ',') &&
std::getline(lineStream, path1, ',') &&
std::getline(lineStream, path2, ',')) {
// 创建目录
std::filesystem::path dirPath = std::filesystem::path(".") / name;
std::filesystem::create_directory(dirPath);
std::filesystem::create_directory(dirPath / "file1");
std::filesystem::create_directory(dirPath / "file2");
// 拷贝文件
std::filesystem::copy_file(path1, dirPath / "file1" / std::filesystem::path(path1).filename(), std::filesystem::copy_options::overwrite_existing);
std::filesystem::copy_file(path2, dirPath / "file2" / std::filesystem::path(path2).filename(), std::filesystem::copy_options::overwrite_existing);
}
}
return 0;
}
```
这个程序使用了C++17中的`std::filesystem`库,需要在编译时加上`-std=c++17 -lstdc++fs`选项。例如,使用`g++`编译可以使用以下命令:
```bash
g++ -std=c++17 -lstdc++fs your_program.cpp -o your_program
```
*/
\ No newline at end of file
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