1- #include " data_conversions.h"
1+ #include < data_conversions.h>
22
3- void setMap (std::shared_ptr<MPL::VoxelMapUtil>& map_util,
4- const planning_ros_msgs::VoxelMap& msg) {
3+ #include < algorithm>
4+
5+ void setMap (const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
6+ const kr_planning_msgs::VoxelMap& msg) {
57 Vec3f ori (msg.origin .x , msg.origin .y , msg.origin .z );
68 Vec3i dim (msg.dim .x , msg.dim .y , msg.dim .z );
79 map_util->setMap (ori, dim, msg.data , msg.resolution );
810}
911
10- void getMap (std::shared_ptr<MPL::VoxelMapUtil>& map_util,
11- planning_ros_msgs ::VoxelMap& map) {
12+ void getMap (const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
13+ kr_planning_msgs ::VoxelMap* map) {
1214 Vec3f ori = map_util->getOrigin ();
1315 Vec3i dim = map_util->getDim ();
1416 double res = map_util->getRes ();
1517
16- map. origin .x = ori (0 );
17- map. origin .y = ori (1 );
18- map. origin .z = ori (2 );
18+ map-> origin .x = ori (0 );
19+ map-> origin .y = ori (1 );
20+ map-> origin .z = ori (2 );
1921
20- map. dim .x = dim (0 );
21- map. dim .y = dim (1 );
22- map. dim .z = dim (2 );
23- map. resolution = res;
22+ map-> dim .x = dim (0 );
23+ map-> dim .y = dim (1 );
24+ map-> dim .z = dim (2 );
25+ map-> resolution = res;
2426
25- map. data = map_util->getMap ();
27+ map-> data = map_util->getMap ();
2628}
2729
28- void setMap (std::shared_ptr<JPS::VoxelMapUtil>& map_util,
29- const planning_ros_msgs ::VoxelMap& msg) {
30+ void setMap (const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
31+ const kr_planning_msgs ::VoxelMap& msg) {
3032 Vec3f ori (msg.origin .x , msg.origin .y , msg.origin .z );
3133 Vec3i dim (msg.dim .x , msg.dim .y , msg.dim .z );
3234 map_util->setMap (ori, dim, msg.data , msg.resolution );
3335}
3436
35- void getMap (std::shared_ptr<JPS::VoxelMapUtil>& map_util,
36- planning_ros_msgs ::VoxelMap& map) {
37+ void getMap (const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
38+ kr_planning_msgs ::VoxelMap* map) {
3739 Vec3f ori = map_util->getOrigin ();
3840 Vec3i dim = map_util->getDim ();
3941 double res = map_util->getRes ();
4042
41- map. origin .x = ori (0 );
42- map. origin .y = ori (1 );
43- map. origin .z = ori (2 );
43+ map-> origin .x = ori (0 );
44+ map-> origin .y = ori (1 );
45+ map-> origin .z = ori (2 );
4446
45- map. dim .x = dim (0 );
46- map. dim .y = dim (1 );
47- map. dim .z = dim (2 );
48- map. resolution = res;
47+ map-> dim .x = dim (0 );
48+ map-> dim .y = dim (1 );
49+ map-> dim .z = dim (2 );
50+ map-> resolution = res;
4951
50- map. data = map_util->getMap ();
52+ map-> data = map_util->getMap ();
5153}
5254
53- void setMap (std::shared_ptr<JPS::OccMapUtil>& map_util,
54- const planning_ros_msgs ::VoxelMap& msg) {
55+ void setMap (const std::shared_ptr<JPS::OccMapUtil>& map_util,
56+ const kr_planning_msgs ::VoxelMap& msg) {
5557 Vec2f ori (msg.origin .x , msg.origin .y );
5658 Vec2i dim (msg.dim .x , msg.dim .y );
5759 map_util->setMap (ori, dim, msg.data , msg.resolution );
5860}
5961
60- void getMap (std::shared_ptr<JPS::OccMapUtil>& map_util,
61- planning_ros_msgs ::VoxelMap& map) {
62+ void getMap (const std::shared_ptr<JPS::OccMapUtil>& map_util,
63+ kr_planning_msgs ::VoxelMap* map) {
6264 Vec2f ori = map_util->getOrigin ();
6365 Vec2i dim = map_util->getDim ();
6466 double res = map_util->getRes ();
6567
66- map. origin .x = ori (0 );
67- map. origin .y = ori (1 );
68- map. origin .z = 0 ;
68+ map-> origin .x = ori (0 );
69+ map-> origin .y = ori (1 );
70+ map-> origin .z = 0 ;
6971
70- map. dim .x = dim (0 );
71- map. dim .y = dim (1 );
72- map. dim .z = 1 ;
73- map. resolution = res;
72+ map-> dim .x = dim (0 );
73+ map-> dim .y = dim (1 );
74+ map-> dim .z = 1 ;
75+ map-> resolution = res;
7476
75- map. data = map_util->getMap ();
77+ map-> data = map_util->getMap ();
7678}
7779
78- planning_ros_msgs::VoxelMap sliceMap (const planning_ros_msgs::VoxelMap& map,
79- double h, double hh) {
80+ kr_planning_msgs::VoxelMap sliceMap (const kr_planning_msgs::VoxelMap& map,
81+ double h,
82+ double hh) {
8083 // slice a 3D voxel map
8184 double res = map.resolution ;
8285 int hhi = hh / res;
@@ -88,7 +91,7 @@ planning_ros_msgs::VoxelMap sliceMap(const planning_ros_msgs::VoxelMap& map,
8891 h_max = h_max <= map.dim .z ? h_max : map.dim .z ;
8992
9093 // slice a 3D voxel map
91- planning_ros_msgs ::VoxelMap voxel_map;
94+ kr_planning_msgs ::VoxelMap voxel_map;
9295 voxel_map.origin .x = map.origin .x ;
9396 voxel_map.origin .y = map.origin .y ;
9497 voxel_map.origin .z = h;
0 commit comments