Skip to content

Commit 552fb8f

Browse files
committed
address linting - change non const refs to pointers
1 parent b65ab65 commit 552fb8f

File tree

2 files changed

+30
-30
lines changed

2 files changed

+30
-30
lines changed

autonomy_core/map_plan/action_planner/src/data_conversions.cpp

Lines changed: 27 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -10,21 +10,21 @@ void setMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
1010
}
1111

1212
void getMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
13-
kr_planning_msgs::VoxelMap& map) {
13+
kr_planning_msgs::VoxelMap* map) {
1414
Vec3f ori = map_util->getOrigin();
1515
Vec3i dim = map_util->getDim();
1616
double res = map_util->getRes();
1717

18-
map.origin.x = ori(0);
19-
map.origin.y = ori(1);
20-
map.origin.z = ori(2);
18+
map->origin.x = ori(0);
19+
map->origin.y = ori(1);
20+
map->origin.z = ori(2);
2121

22-
map.dim.x = dim(0);
23-
map.dim.y = dim(1);
24-
map.dim.z = dim(2);
25-
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;
2626

27-
map.data = map_util->getMap();
27+
map->data = map_util->getMap();
2828
}
2929

3030
void setMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
@@ -35,21 +35,21 @@ void setMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
3535
}
3636

3737
void getMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
38-
kr_planning_msgs::VoxelMap& map) {
38+
kr_planning_msgs::VoxelMap* map) {
3939
Vec3f ori = map_util->getOrigin();
4040
Vec3i dim = map_util->getDim();
4141
double res = map_util->getRes();
4242

43-
map.origin.x = ori(0);
44-
map.origin.y = ori(1);
45-
map.origin.z = ori(2);
43+
map->origin.x = ori(0);
44+
map->origin.y = ori(1);
45+
map->origin.z = ori(2);
4646

47-
map.dim.x = dim(0);
48-
map.dim.y = dim(1);
49-
map.dim.z = dim(2);
50-
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;
5151

52-
map.data = map_util->getMap();
52+
map->data = map_util->getMap();
5353
}
5454

5555
void setMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
@@ -60,21 +60,21 @@ void setMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
6060
}
6161

6262
void getMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
63-
kr_planning_msgs::VoxelMap& map) {
63+
kr_planning_msgs::VoxelMap* map) {
6464
Vec2f ori = map_util->getOrigin();
6565
Vec2i dim = map_util->getDim();
6666
double res = map_util->getRes();
6767

68-
map.origin.x = ori(0);
69-
map.origin.y = ori(1);
70-
map.origin.z = 0;
68+
map->origin.x = ori(0);
69+
map->origin.y = ori(1);
70+
map->origin.z = 0;
7171

72-
map.dim.x = dim(0);
73-
map.dim.y = dim(1);
74-
map.dim.z = 1;
75-
map.resolution = res;
72+
map->dim.x = dim(0);
73+
map->dim.y = dim(1);
74+
map->dim.z = 1;
75+
map->resolution = res;
7676

77-
map.data = map_util->getMap();
77+
map->data = map_util->getMap();
7878
}
7979

8080
kr_planning_msgs::VoxelMap sliceMap(const kr_planning_msgs::VoxelMap& map,

autonomy_core/map_plan/action_planner/src/data_conversions.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,19 +10,19 @@ void setMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
1010
const kr_planning_msgs::VoxelMap& msg);
1111

1212
void getMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
13-
kr_planning_msgs::VoxelMap& map);
13+
kr_planning_msgs::VoxelMap* map);
1414

1515
void setMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
1616
const kr_planning_msgs::VoxelMap& msg);
1717

1818
void getMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
19-
kr_planning_msgs::VoxelMap& map);
19+
kr_planning_msgs::VoxelMap* map);
2020

2121
void setMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
2222
const kr_planning_msgs::VoxelMap& msg);
2323

2424
void getMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
25-
kr_planning_msgs::VoxelMap& map);
25+
kr_planning_msgs::VoxelMap* map);
2626

2727
// NOTE: This function is the same as getInflatedOccMap function in
2828
// voxel_mapper.cpp, should merge them.

0 commit comments

Comments
 (0)