Skip to content

Commit 017fdc9

Browse files
authored
Merge pull request #44 from AutoModality/BB-424/collision_avoidance
Bb 424/collision avoidance
2 parents 966e81b + 46dbebc commit 017fdc9

File tree

8 files changed

+80
-26
lines changed

8 files changed

+80
-26
lines changed

include/vb_util_lib/current_enu_kinematics.h

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,18 +9,17 @@
99
#define VISBOX_PACKAGES_COMMON_UTILS_UTIL_LIB_INCLUDE_CURRENTENUKINEMATICS_H_
1010

1111
#include <vb_util_lib/kinematics.h>
12+
#include <vb_util_lib/topics.h>
1213
#include <nav_msgs/Odometry.h>
1314
#include <std_msgs/Float64.h>
1415

1516
#include <vb_util_lib/transformer.h>
1617

17-
#define VEHICLE_CURRENT_ENU_TOPIC "/ctrl/vx/vehicle/currentENU"
18-
1918
class CurrentENUKinematics: public Kinematics {
2019
public:
2120
CurrentENUKinematics();
2221

23-
CurrentENUKinematics(ros::NodeHandle *n, std::string topic=VEHICLE_CURRENT_ENU_TOPIC,
22+
CurrentENUKinematics(ros::NodeHandle *n, std::string topic=am::am_topics::CTRL_VX_VEHICLE_CURRENTENU,
2423
bool pub_on_change=false, double pub_rate=0.0);
2524

2625
virtual ~CurrentENUKinematics();

include/vb_util_lib/gps_location.h

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,6 @@
1515

1616
using namespace am;
1717

18-
#define DEFAULT_GPS_LOCATION_TOPIC "/ctrl/vx/gps_location"
19-
2018
/**
2119
* Wrapper method for the global GPS location.
2220
* Can use this class either as a publisher or a subscriber for the GPS Location.
@@ -28,7 +26,7 @@ using namespace am;
2826
class GPSLocation {
2927
public:
3028
GPSLocation() {};
31-
GPSLocation(ros::NodeHandle *n, std::string topic=DEFAULT_GPS_LOCATION_TOPIC,
29+
GPSLocation(ros::NodeHandle *n, std::string topic=am::am_topics::CTRL_VX_GPS_LOCATION,
3230
bool pub_on_change=false, double pub_rate=0.0) :
3331
topic_(topic), pub_on_change_(pub_on_change), pub_rate_(pub_rate) {
3432
initROS(n);

include/vb_util_lib/kinematics.h

Lines changed: 1 addition & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -35,23 +35,12 @@
3535
//#include <brain_box_msgs/VxKinematics.h>
3636
#include <visualization_msgs/Marker.h>
3737

38+
#include <vb_util_lib/topics.h>
3839
#include <vb_util_lib/control_util.h>
3940
#include <vb_util_lib/am_geometry.h>
4041
#include <vb_util_lib/transformer.h>
4142
#include <vb_util_lib/frame_names.h>
4243

43-
#define VEHICLE_CURRENT_ENU_TOPIC "/ctrl/vx/vehicle/currentENU"
44-
#define VEHICLE_COMMAND_ENU_TOPIC "/ctrl/vx/vehicle/commandENU"
45-
#define VEHICLE_SETPOINT_ENU_TOPIC "/ctrl/vx/vehicle/setpointENU"
46-
47-
#define VEHICLE_CURRENT_NED_TOPIC "/ctrl/vx/vehicle/currentNED"
48-
#define VEHICLE_COMMAND_NED_TOPIC "/ctrl/vx/vehicle/commandNED"
49-
#define VEHICLE_SETPOINT_NED_TOPIC "/ctrl/vx/vehicle/setpointNED"
50-
51-
#define VEHICLE_SETPOINT_ATTITUDE_TOPIC "/ctrl/vx/vehicle/att_cmd"
52-
#define VEHICLE_SETPOINT_RELPOS_TOPIC "/ctrl/vx/vehicle/relpos_cmd"
53-
#define VEHICLE_SETPOINT_ABSPOS_TOPIC "/ctrl/vx/vehicle/abspos_cmd"
54-
5544
/**
5645
* Wrapper method for vehicle Kinematics
5746
* Can use this class either as a publisher or a subscriber for the state information.

include/vb_util_lib/mission_status.h

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,15 +10,14 @@
1010

1111
#include <brain_box_msgs/VxMissionStatus.h>
1212
#include <brain_box_msgs/VxFlightPlanStatus.h>
13+
#include <vb_util_lib/topics.h>
1314

1415
#include <ros/ros.h>
1516

16-
#define DEFAULT_MISSION_STATUS_TOPIC "/ctrl/vx/mission_status"
17-
1817
class MissionStatus {
1918
public:
2019
MissionStatus() {};
21-
MissionStatus(ros::NodeHandle *n, std::string topic=DEFAULT_MISSION_STATUS_TOPIC,
20+
MissionStatus(ros::NodeHandle *n, std::string topic=am::am_topics::CTRL_VX_MISSION_STATUS,
2221
bool pub_on_change=false, double pub_rate=0.0) :
2322
topic_(topic), pub_on_change_(pub_on_change), pub_rate_(pub_rate) {
2423
initROS(n);

include/vb_util_lib/target_enu_kinematics.h

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,16 +3,15 @@
33

44
#include <vb_util_lib/kinematics.h>
55
#include <nav_msgs/Odometry.h>
6+
#include <vb_util_lib/topics.h>
67
// #include <vb_util_lib/bag_logger.h> // TODO (dan) bag_logger
78

8-
#define TARGET_CURRENT_ENU_TOPIC "/ctrl/vx/target/currentENU"
9-
109
class TargetENUKinematics: public Kinematics {
1110
public:
1211
TargetENUKinematics();
13-
TargetENUKinematics(ros::NodeHandle *n, std::string topic=TARGET_CURRENT_ENU_TOPIC,
12+
TargetENUKinematics(ros::NodeHandle *n, std::string topic=am::am_topics::CTRL_VX_TARGET_CURRENT_ENU,
1413
bool pub_on_change=false, double pub_rate=0.0) :
15-
Kinematics(n, topic!="" ? topic : TARGET_CURRENT_ENU_TOPIC,
14+
Kinematics(n, topic!="" ? topic : am::am_topics::CTRL_VX_TARGET_CURRENT_ENU,
1615
Asset_ENU, pub_on_change, pub_rate) {
1716
}
1817
virtual ~TargetENUKinematics() {};

include/vb_util_lib/topics.h

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
#ifndef VB_UTIL_LIB_AM_TOPICS_H
22
#define VB_UTIL_LIB_AM_TOPICS_H
33

4+
#include <string>
5+
46
namespace am
57
{
68

@@ -154,6 +156,40 @@ class am_topics
154156
static constexpr char STATUS_SS1[] = "/status/ss1";
155157
static constexpr char STATUS_SS2[] = "/status/ss2";
156158

159+
// visbox CTRL messages
160+
static constexpr char CTRL_VX_CMND[] = "/ctrl/vx/cmnd";
161+
static constexpr char CTRL_VX_FCU_STATUS[] = "/ctrl/vx/fcu_status";
162+
static constexpr char CTRL_VX_FLIGHT_CONTROL[] = "/ctrl/vx/flight_control";
163+
static constexpr char CTRL_VX_FLIGHTPLAN[] = "/ctrl/vx/flightplan";
164+
static constexpr char CTRL_VX_FLIGHTPAN_STATUS[] = "/ctrl/vx/flightplan/status";
165+
static constexpr char CTRL_VX_GLOBAL_POS_NAV_ACTION[] = "/ctrl/vx/global_pos_nav_action";
166+
static constexpr char CTRL_VX_GPS_LOCATION[] = "/ctrl/vx/gps_location";
167+
static constexpr char CTRL_VX_LOCAL_POS_NAV_ACTION[] = "/ctrl/vx/local_pos_nav_action";
168+
static constexpr char CTRL_VX_MISSION[] = "/ctrl/vx/mission";
169+
static constexpr char CTRL_VX_MISSION_MESSAGE[] = "/ctrl/vx/mission/message";
170+
static constexpr char CTRL_VX_MISSION_STATUS[] = "/ctrl/vx/mission_status";
171+
static constexpr char CTRL_VX_PID_PARAM[] = "/ctrl/vx/pid_param";
172+
static constexpr char CTRL_VX_PROXIMITY[] = "/ctrl/vx/proximity";
173+
static constexpr char CTRL_VX_RTL_ACTION[] = "/ctrl/vx/rtl_action";
174+
static constexpr char CTRL_VX_TARGET_CURRENT_ENU[] = "/ctrl/vx/target/currentENU";
175+
static constexpr char CTRL_VX_VEHICLE_CURRENTENU[] = "/ctrl/vx/vehicle/currentENU";
176+
static constexpr char CTRL_VX_VELOCITY[] = "/ctrl/vx/velocity";
177+
static constexpr char CTRL_VX_WAYPOINT_NAV_ACTION [] = "/ctrl/vx/waypoint_nav_action";
178+
179+
static constexpr char CTRL_FEATURE_STATUS_LIST[] = "/ctrl/feature_status_list";
180+
static constexpr char CTRL_FEATURE_STATUS[] = "/ctrl/feature_status";
181+
static constexpr char CTRL_FEATURE_STATUS_UPDATE[] = "/ctrl/feature_status_update";
182+
static constexpr char CTRL_FEATURE_END_LIST[] = "/ctrl/feature_end_list";
183+
184+
static constexpr char CTRL_DEPTH_CMND[] = "/ctrl/depth/cmnd";
185+
static constexpr char CTRL_LOG_CONTROL[] = "/ctrl/log_control";
186+
static constexpr char CTRL_ROUTE[] = "/ctrl/route";
187+
static constexpr char CTRL_VIDEO_CMND[] = "/ctrl/video/cmnd";
188+
static constexpr char CTRL_VISION_CMND[] = "/ctrl/vision/cmnd";
189+
static constexpr char CTRL_VISION_MARKER_OFFSET[] = "/ctrl/vision/marker_offset";
190+
191+
static constexpr char REMOTE_CTRL_VX_MISSION[] = "/remote/ctrl/vx/mission";
192+
157193
static constexpr char LED_BLINK[] = "/blinkm_command";
158194
static constexpr char BATTERY_STATE[] = "/dji_sdk/battery_state";
159195

src/vb_util_lib/current_enu_kinematics.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ CurrentENUKinematics::CurrentENUKinematics() {
1515

1616
CurrentENUKinematics::CurrentENUKinematics(ros::NodeHandle *n, std::string topic,
1717
bool pub_on_change, double pub_rate) :
18-
Kinematics(n, topic!="" ? topic : VEHICLE_CURRENT_ENU_TOPIC,
18+
Kinematics(n, topic!="" ? topic : am::am_topics::CTRL_VX_VEHICLE_CURRENTENU,
1919
Asset_ENU, pub_on_change, pub_rate) {
2020

2121
//tfListener_ = new tf2_ros::TransformListener(tfBuffer);

src/vb_util_lib/topics.cpp

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ constexpr char am_topics::DJI_SDK_RELATIVE_POSITION[];
2828
constexpr char am_topics::DJI_SDK_ODOMETRY[];
2929
constexpr char am_topics::DJI_SDK_SEND_DATA_TO_MOBILE[];
3030
constexpr char am_topics::DJI_SDK_CORRECTED_ATTITUDE[];
31+
3132
constexpr char am_topics::FEATURE_ODOMETRY[];
3233
constexpr char am_topics::FEATURE_SEARCH_IDS[];
3334

@@ -86,6 +87,39 @@ constexpr char am_topics::STATUS_LIDAR[];
8687
constexpr char am_topics::STATUS_SS1[];
8788
constexpr char am_topics::STATUS_SS2[];
8889

90+
constexpr char am_topics::CTRL_VX_CMND[];
91+
constexpr char am_topics::CTRL_VX_FCU_STATUS[];
92+
constexpr char am_topics::CTRL_VX_FLIGHT_CONTROL[];
93+
constexpr char am_topics::CTRL_VX_FLIGHTPLAN[];
94+
constexpr char am_topics::CTRL_VX_FLIGHTPAN_STATUS[];
95+
constexpr char am_topics::CTRL_VX_GLOBAL_POS_NAV_ACTION[];
96+
constexpr char am_topics::CTRL_VX_GPS_LOCATION[];
97+
constexpr char am_topics::CTRL_VX_LOCAL_POS_NAV_ACTION[];
98+
constexpr char am_topics::CTRL_VX_MISSION[];
99+
constexpr char am_topics::CTRL_VX_MISSION_MESSAGE[];
100+
constexpr char am_topics::CTRL_VX_MISSION_STATUS[];
101+
constexpr char am_topics::CTRL_VX_PID_PARAM[];
102+
constexpr char am_topics::CTRL_VX_PROXIMITY[];
103+
constexpr char am_topics::CTRL_VX_RTL_ACTION[];
104+
constexpr char am_topics::CTRL_VX_TARGET_CURRENT_ENU[];
105+
constexpr char am_topics::CTRL_VX_VEHICLE_CURRENTENU[];
106+
constexpr char am_topics::CTRL_VX_VELOCITY[];
107+
constexpr char am_topics::CTRL_VX_WAYPOINT_NAV_ACTION[];
108+
109+
constexpr char am_topics::CTRL_FEATURE_STATUS_LIST[];
110+
constexpr char am_topics::CTRL_FEATURE_STATUS[];
111+
constexpr char am_topics::CTRL_FEATURE_STATUS_UPDATE[];
112+
constexpr char am_topics::CTRL_FEATURE_END_LIST[];
113+
114+
constexpr char am_topics::CTRL_DEPTH_CMND[];
115+
constexpr char am_topics::CTRL_LOG_CONTROL[];
116+
constexpr char am_topics::CTRL_ROUTE[];
117+
constexpr char am_topics::CTRL_VIDEO_CMND[];
118+
constexpr char am_topics::CTRL_VISION_CMND[];
119+
constexpr char am_topics::CTRL_VISION_MARKER_OFFSET[];
120+
121+
constexpr char am_topics::REMOTE_CTRL_VX_MISSION[];
122+
89123
constexpr char am_topics::LED_BLINK[];
90124
constexpr char am_topics::BATTERY_STATE[];
91125

0 commit comments

Comments
 (0)