Skip to content

Commit 2cd6fd9

Browse files
committed
* rename planning_ros_msgs -> kr_planning_msgs
* rename planning_ros_utils -> kr_planning_rviz_plugins * remove both of the above from kr_autonomous flight (todo: add to external repos) * move primitive_ros_utils (converts btw MPL and kr_planning_msgs) to the action_planner since it is only used there * still todo: data_type.h (defines common datatypes like Vec3f) and data_ros_utils (random data conversions) should not live in kr_planning_rviz_plugins, and should be in some common location. data_type is also copied from mpl/jps. state_machine, action_trackers, and action_planner are the packages that use data_ros_utils
1 parent 9d9a87e commit 2cd6fd9

File tree

94 files changed

+303
-3597
lines changed

Some content is hidden

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

94 files changed

+303
-3597
lines changed

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: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
#include "data_conversions.h"
22

33
void setMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
4-
const planning_ros_msgs::VoxelMap& msg) {
4+
const kr_planning_msgs::VoxelMap& msg) {
55
Vec3f ori(msg.origin.x, msg.origin.y, msg.origin.z);
66
Vec3i dim(msg.dim.x, msg.dim.y, msg.dim.z);
77
map_util->setMap(ori, dim, msg.data, msg.resolution);
88
}
99

1010
void getMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
11-
planning_ros_msgs::VoxelMap& map) {
11+
kr_planning_msgs::VoxelMap& map) {
1212
Vec3f ori = map_util->getOrigin();
1313
Vec3i dim = map_util->getDim();
1414
double res = map_util->getRes();
@@ -26,14 +26,14 @@ void getMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
2626
}
2727

2828
void setMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
29-
const planning_ros_msgs::VoxelMap& msg) {
29+
const kr_planning_msgs::VoxelMap& msg) {
3030
Vec3f ori(msg.origin.x, msg.origin.y, msg.origin.z);
3131
Vec3i dim(msg.dim.x, msg.dim.y, msg.dim.z);
3232
map_util->setMap(ori, dim, msg.data, msg.resolution);
3333
}
3434

3535
void getMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
36-
planning_ros_msgs::VoxelMap& map) {
36+
kr_planning_msgs::VoxelMap& map) {
3737
Vec3f ori = map_util->getOrigin();
3838
Vec3i dim = map_util->getDim();
3939
double res = map_util->getRes();
@@ -51,14 +51,14 @@ void getMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
5151
}
5252

5353
void setMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
54-
const planning_ros_msgs::VoxelMap& msg) {
54+
const kr_planning_msgs::VoxelMap& msg) {
5555
Vec2f ori(msg.origin.x, msg.origin.y);
5656
Vec2i dim(msg.dim.x, msg.dim.y);
5757
map_util->setMap(ori, dim, msg.data, msg.resolution);
5858
}
5959

6060
void getMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
61-
planning_ros_msgs::VoxelMap& map) {
61+
kr_planning_msgs::VoxelMap& map) {
6262
Vec2f ori = map_util->getOrigin();
6363
Vec2i dim = map_util->getDim();
6464
double res = map_util->getRes();
@@ -75,7 +75,7 @@ void getMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
7575
map.data = map_util->getMap();
7676
}
7777

78-
planning_ros_msgs::VoxelMap sliceMap(const planning_ros_msgs::VoxelMap& map,
78+
kr_planning_msgs::VoxelMap sliceMap(const kr_planning_msgs::VoxelMap& map,
7979
double h, double hh) {
8080
// slice a 3D voxel map
8181
double res = map.resolution;
@@ -88,7 +88,7 @@ planning_ros_msgs::VoxelMap sliceMap(const planning_ros_msgs::VoxelMap& map,
8888
h_max = h_max <= map.dim.z ? h_max : map.dim.z;
8989

9090
// slice a 3D voxel map
91-
planning_ros_msgs::VoxelMap voxel_map;
91+
kr_planning_msgs::VoxelMap voxel_map;
9292
voxel_map.origin.x = map.origin.x;
9393
voxel_map.origin.y = map.origin.y;
9494
voxel_map.origin.z = h;

autonomy_core/map_plan/action_planner/src/data_conversions.h

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,27 +2,27 @@
22

33
#include <jps/map_util.h>
44
#include <mpl_collision/map_util.h>
5-
#include <planning_ros_msgs/VoxelMap.h>
5+
#include <kr_planning_msgs/VoxelMap.h>
66

77
void setMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
8-
const planning_ros_msgs::VoxelMap& msg);
8+
const kr_planning_msgs::VoxelMap& msg);
99

1010
void getMap(std::shared_ptr<MPL::VoxelMapUtil>& map_util,
11-
planning_ros_msgs::VoxelMap& map);
11+
kr_planning_msgs::VoxelMap& map);
1212

1313
void setMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
14-
const planning_ros_msgs::VoxelMap& msg);
14+
const kr_planning_msgs::VoxelMap& msg);
1515

1616
void getMap(std::shared_ptr<JPS::VoxelMapUtil>& map_util,
17-
planning_ros_msgs::VoxelMap& map);
17+
kr_planning_msgs::VoxelMap& map);
1818

1919
void setMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
20-
const planning_ros_msgs::VoxelMap& msg);
20+
const kr_planning_msgs::VoxelMap& msg);
2121

2222
void getMap(std::shared_ptr<JPS::OccMapUtil>& map_util,
23-
planning_ros_msgs::VoxelMap& map);
23+
kr_planning_msgs::VoxelMap& map);
2424

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

0 commit comments

Comments
 (0)