Skip to content

Commit c51e64e

Browse files
authored
Merge pull request #160 from KumarRobotics/feature/remove_planning_ros_msgs
Move planning_ros_msgs to be an external dependency
2 parents 5a95942 + e373c76 commit c51e64e

File tree

103 files changed

+442
-3711
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

103 files changed

+442
-3711
lines changed

.github/workflows/cpplint-reviewdog.yaml

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ jobs:
55
cpplint:
66
runs-on: ubuntu-latest
77
steps:
8-
- uses: actions/checkout@master
9-
- uses: reviewdog/action-cpplint@master
10-
with:
11-
github_token: ${{ secrets.KR_AUTONOMOUS_FLIGHT_TOKEN_REVIEWDOG }}
12-
reporter: github-pr-check
13-
flags: --exclude=autonomy_core/map_plan/jps3d/include/jps/graph_search.h --exclude autonomy_core/map_plan/jps3d/src/graph_search.cpp --exclude autonomy_core/map_plan/planning_ros_utils/src/planning_rviz_plugins/map_display.h --exclude autonomy_core/state_machine/action_trackers/src/take_off_tracker.cpp --exclude autonomy_core/map_plan/mpl/include/mpl_basis/lambda.h --exclude autonomy_core/map_plan/mpl/include/mpl_planner/env_base.h --exclude autonomy_core/map_plan/mpl/src/env_base.cpp --exclude autonomy_core/map_plan/mpl/src/env_map.cpp
14-
filter: "-whitespace/comments,-whitespace/indent,-build/include_order,-whitespace/ending_newline,-runtime/references"
15-
# Note: runtime/references was added to address google benchmark
16-
# issues, as requested by https://github.com/KumarRobotics/kr_autonomous_flight/pull/171
8+
- uses: actions/checkout@master
9+
- uses: reviewdog/action-cpplint@master
10+
with:
11+
github_token: ${{ secrets.KR_AUTONOMOUS_FLIGHT_TOKEN_REVIEWDOG }}
12+
reporter: github-pr-check
13+
flags: --exclude=autonomy_core/map_plan/jps3d/include/jps/graph_search.h --exclude autonomy_core/map_plan/jps3d/src/graph_search.cpp --exclude autonomy_core/state_machine/action_trackers/src/take_off_tracker.cpp --exclude autonomy_core/map_plan/mpl/include/mpl_basis/lambda.h --exclude autonomy_core/map_plan/mpl/include/mpl_planner/env_base.h --exclude autonomy_core/map_plan/mpl/src/env_base.cpp --exclude autonomy_core/map_plan/mpl/src/env_map.cpp
14+
filter: "-whitespace/comments,-whitespace/indent,-build/include_order,-whitespace/ending_newline,-runtime/references"
15+
# Note: runtime/references was added to address google benchmark
16+
# issues, as requested by https://github.com/KumarRobotics/kr_autonomous_flight/pull/171

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@ mrsl_quadrotor/
44
msckf_vio/
55
ouster_example/
66
waypoint_navigation_plugin/
7+
kr_planning_msgs/
78

89
#===========
910
# C++

autonomy_core/client/client_launch/rviz/client.rviz

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,7 @@ Visualization Manager:
7676
Show Arrows: true
7777
Show Axes: true
7878
Show Names: true
79-
Tree:
80-
{}
79+
Tree: {}
8180
Update Interval: 0
8281
Value: false
8382
- Class: rviz/InteractiveMarkers
@@ -95,15 +94,14 @@ Visualization Manager:
9594
Enabled: true
9695
Marker Topic: /env_vis/env
9796
Name: Environment
98-
Namespaces:
99-
{}
97+
Namespaces: {}
10098
Queue Size: 100
10199
Value: true
102100
Enabled: false
103101
Name: Env
104102
- Class: rviz/Group
105103
Displays:
106-
- Class: planning_rviz_plugins/Path
104+
- Class: kr_planning_rviz_plugins/Path
107105
Enabled: true
108106
LineColor: 204; 51; 204
109107
LineScale: 0.4000000059604645
@@ -114,7 +112,7 @@ Visualization Manager:
114112
Topic: /quadrotor/global_plan_server/path
115113
Unreliable: false
116114
Value: true
117-
- Class: planning_rviz_plugins/Path
115+
- Class: kr_planning_rviz_plugins/Path
118116
Enabled: true
119117
LineColor: 0; 255; 0
120118
LineScale: 0.800000011920929
@@ -153,7 +151,7 @@ Visualization Manager:
153151
Use Fixed Frame: true
154152
Use rainbow: true
155153
Value: true
156-
- Class: planning_rviz_plugins/Path
154+
- Class: kr_planning_rviz_plugins/Path
157155
Enabled: true
158156
LineColor: 78; 154; 6
159157
LineScale: 0.800000011920929
@@ -167,7 +165,7 @@ Visualization Manager:
167165
- AccColor: 10; 200; 55
168166
AccScale: 0.014999999664723873
169167
AccVis: true
170-
Class: planning_rviz_plugins/Trajectory
168+
Class: kr_planning_rviz_plugins/Trajectory
171169
Enabled: true
172170
JrkColor: 200; 20; 55
173171
JrkScale: 0.014999999664723873
@@ -189,7 +187,7 @@ Visualization Manager:
189187
YawTriangleAngle: 0.699999988079071
190188
YawTriangleScale: 0.5
191189
YawVis: true
192-
- Class: planning_rviz_plugins/Path
190+
- Class: kr_planning_rviz_plugins/Path
193191
Enabled: true
194192
LineColor: 0; 170; 255
195193
LineScale: 0.5
@@ -222,7 +220,7 @@ Visualization Manager:
222220
Axis: Z
223221
BoundScale: 0.5
224222
Channel Name: intensity
225-
Class: planning_rviz_plugins/VoxelMap
223+
Class: kr_planning_rviz_plugins/VoxelMap
226224
Color: 239; 41; 41
227225
Color Transformer: AxisColor
228226
Decay Time: 0
@@ -255,7 +253,7 @@ Visualization Manager:
255253
Axis: Z
256254
BoundScale: 3
257255
Channel Name: intensity
258-
Class: planning_rviz_plugins/VoxelMap
256+
Class: kr_planning_rviz_plugins/VoxelMap
259257
Color: 252; 233; 79
260258
Color Transformer: FlatColor
261259
Decay Time: 0

autonomy_core/client/rqt_quadrotor_safety/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
<buildtool_depend>catkin</buildtool_depend>
1515

1616
<run_depend>geometry_msgs</run_depend>
17-
<run_depend>planning_ros_msgs</run_depend>
17+
<run_depend>kr_planning_msgs</run_depend>
1818
<run_depend>mavros_msgs</run_depend>
1919
<run_depend>python-rospkg</run_depend>
2020
<run_depend>rostopic</run_depend>

autonomy_core/client/rqt_quadrotor_safety/src/rqt_quadrotor_safety/quadrotor_safety.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
from rqt_gui_py.plugin import Plugin
1919

2020
import std_msgs.msg
21-
import planning_ros_msgs.msg as MHL
21+
import kr_planning_msgs.msg as MHL
2222
from nav_msgs.msg import Odometry
2323
import kr_mav_msgs.msg as QM
2424
import numpy as np

autonomy_core/map_plan/action_planner/CMakeLists.txt

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -15,17 +15,17 @@ find_package(
1515
pcl_ros
1616
mapper
1717
jps3d
18-
planning_ros_utils
19-
planning_ros_msgs
18+
kr_planning_rviz_plugins
19+
kr_planning_msgs
2020
traj_opt_ros
2121
dynamic_reconfigure
2222
motion_primitive_library)
2323

2424
generate_dynamic_reconfigure_options(cfg/ActionPlanner.cfg)
2525

26-
catkin_package(CATKIN_DEPENDS dynamic_reconfigure planning_ros_msgs)
26+
catkin_package(CATKIN_DEPENDS dynamic_reconfigure kr_planning_msgs)
2727

28-
add_library(${PROJECT_NAME} src/data_conversions.cpp)
28+
add_library(${PROJECT_NAME} src/data_conversions.cpp src/primitive_ros_utils.cpp)
2929
target_include_directories(${PROJECT_NAME} PUBLIC src ${catkin_INCLUDE_DIRS})
3030
target_link_libraries(${PROJECT_NAME} PUBLIC ${catkin_LIBRARIES})
3131

autonomy_core/map_plan/action_planner/package.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@
2626
<depend>pcl_ros</depend>
2727
<depend>mapper</depend>
2828
<depend>jps3d</depend>
29-
<depend>planning_ros_utils</depend>
30-
<depend>planning_ros_msgs</depend>
29+
<depend>kr_planning_rviz_plugins</depend>
30+
<depend>kr_planning_msgs</depend>
3131
<depend>traj_opt_ros</depend>
3232
<depend>motion_primitive_library</depend>
3333

autonomy_core/map_plan/action_planner/src/data_conversions.cpp

Lines changed: 43 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,82 +1,85 @@
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;
Lines changed: 18 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,28 +1,31 @@
11
#pragma once
22

33
#include <jps/map_util.h>
4+
#include <kr_planning_msgs/VoxelMap.h>
45
#include <mpl_collision/map_util.h>
5-
#include <planning_ros_msgs/VoxelMap.h>
6+
#include <memory>
67

7-
void setMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
8-
const planning_ros_msgs::VoxelMap& msg);
98

10-
void getMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
11-
planning_ros_msgs::VoxelMap& map);
9+
void setMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
10+
const kr_planning_msgs::VoxelMap& msg);
1211

13-
void setMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
14-
const planning_ros_msgs::VoxelMap& msg);
12+
void getMap(const std::shared_ptr<MPL::VoxelMapUtil>& map_util,
13+
kr_planning_msgs::VoxelMap* map);
1514

16-
void getMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
17-
planning_ros_msgs::VoxelMap& map);
15+
void setMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
16+
const kr_planning_msgs::VoxelMap& msg);
1817

19-
void setMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
20-
const planning_ros_msgs::VoxelMap& msg);
18+
void getMap(const std::shared_ptr<JPS::VoxelMapUtil>& map_util,
19+
kr_planning_msgs::VoxelMap* map);
2120

22-
void getMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
23-
planning_ros_msgs::VoxelMap& map);
21+
void setMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
22+
const kr_planning_msgs::VoxelMap& msg);
23+
24+
void getMap(const std::shared_ptr<JPS::OccMapUtil>& map_util,
25+
kr_planning_msgs::VoxelMap* map);
2426

2527
// NOTE: This function is the same as getInflatedOccMap function in
2628
// voxel_mapper.cpp, should merge them.
27-
planning_ros_msgs::VoxelMap sliceMap(const planning_ros_msgs::VoxelMap& map,
28-
double h, double hh = 0);
29+
kr_planning_msgs::VoxelMap sliceMap(const kr_planning_msgs::VoxelMap& map,
30+
double h,
31+
double hh = 0);

0 commit comments

Comments
 (0)