Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
425 changes: 210 additions & 215 deletions brain_box_msgs/CMakeLists.txt

Large diffs are not rendered by default.

224 changes: 224 additions & 0 deletions brain_box_msgs/CMakeLists_org.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,224 @@
cmake_minimum_required(VERSION 2.8.3)
project(brain_box_msgs)

find_package(catkin REQUIRED COMPONENTS
message_generation
geometry_msgs
nav_msgs
uuid_msgs
genmsg
actionlib_msgs
actionlib
std_msgs
sensor_msgs
shape_msgs)

###################################
## catkin specific configuration ##
###################################
add_message_files(
DIRECTORY msg
FILES
AMMap.msg
BabySitterStatus.msg
BBAttitude.msg
BBGlobalPosition.msg
BBLatency.msg
BBVxCommand.msg
BeaconRangeMsg.msg
BlinkMCommand.msg
BoundingBox.msg
BoundingBoxes.msg
C2Status.msg
CeilingHist.msg
CeilingPC2.msg
CeilingStatus.msg
Collision.msg
CollisionView.msg
CollisionViews.msg
CommsStatus.msg
ControllerState.msg
ControlVariables.msg
CorrFrontHist.msg
CorrSidesHist.msg
CorrSidesYawList.msg
CorrStatus.msg
CRUD.msg
DelayStats.msg
DepthCmnd.msg
DepthStatus.msg
EdgeHist.msg
EdgeStatus.msg
FeatureStatus.msg
FeatureStatusList.msg
FeatureStatusPose.msg
FlightSegment.msg
FlightSegments.msg
FlightSegmentStatus.msg
Float32ArrayStamped.msg
FTPCmnd.msg
FTPStatus.msg
Gimbal.msg
GimbalPose.msg
GISEntity.msg
GPSLocation.msg
GSAMStatus.msg
GSCommand.msg
GSHeader.msg
GSMSDKStatus.msg
GSPNStatus.msg
GuidanceStatus.msg
Int32Stamped.msg
Heartbeat.msg
KeyValue.msg
LidarStatus.msg
LifeCycleState.msg
LifeCycleCommand.msg
Line.msg
LineP2P.msg
LaserCluster.msg
LaserClusters.msg
Latency_Image.msg
Latency_LaserScan.msg
Latency_Odometry.msg
Latency_PointCloud.msg
Latency_PointCloud2.msg
Latency_PoseStamped.msg
Latency_PoseWithCovarianceStamped.msg
Latency_TwistStamped.msg
Latency_TwistWithCovarianceStamped.msg
Latency.msg
LatencyHeader.msg
LocationCoord.msg
LocationSource.msg
LogControl.msg
MarkerConfig.msg
MarkerConfigFamily.msg
MarkDetectStatus.msg
MarkerStatus.msg
MarkerType.msg
MaxMinAve.msg
NodeStatus.msg
NormalsStamped.msg
NormalWithPoint.msg
NormalsWithPointsStamped.msg
OdomLatency.msg
OperatorCommand.msg
OperatorMsg.msg
PassageFeature.msg
PassageFeatures.msg
PassageFeatureWindow.msg
PolarPointCloud.msg
PanelStatus.msg
PanelHist.msg
ProximityVector.msg
ProximityList.msg
PIDParam.msg
Point2.msg
Profiling.msg
ProfilingArray.msg
Range.msg
RangeBall.msg
RGB.msg
Row.msg
RowView.msg
RPYMsgs.msg
Segment.msg
SegmentationIndicesStamped.msg
SegmentationStamped.msg
SegmentIndex.msg
SeqNo.msg
SPStatus.msg
Status.msg
SSStatus.msg
SCStatus.msg
StampedAltimeter.msg
StampedHeartBeat.msg
StampedInterruptTime.msg
StationStatus.msg
SuperNodeStatus.msg
SuperStatus.msg
Super2Status.msg
SystemReport.msg
SystemState.msg
TargetPose.msg
TargetPoseArray.msg
VideoCmnd.msg
VideoStatus.msg
VisionCmnd.msg
VisionStatus.msg
VisLogStatus.msg
VxFCUStatus.msg
VxFeaturePose.msg
VxFlightPlanCmd.msg
VxFlightPlanStatus.msg
VxKinematics.msg
VxManeuver.msg
VxMilestone.msg
VxMissionExecCmd.msg
VxMissionStatus.msg
VxProximity.msg
VxState.msg
VxTrajectory.msg
VxTrajectorySegment.msg
VxTrajectoryStatus.msg
VxYaw.msg
ZEDStatus.msg
)

add_service_files(
DIRECTORY srv
FILES
AMMapBoundingBoxQuery.srv
AttitudeControl.srv
CameraActionControl.srv
CameraSelect.srv
DroneTaskControl.srv
GetAMMap.srv
GimbalAngleControl.srv
GimbalSpeedControl.srv
GlobalPositionControl.srv
LocalPositionControl.srv
SDKPermissionControl.srv
SegmentSearch.srv
VelocityControl.srv
VxFlightPlan.srv
VxMissionExec.srv)

add_action_files(
DIRECTORY action
FILES
CheckForObjects.action
GlobalPositionNavigation.action
LocalPositionNavigation.action
WaypointNavigation.action
Launch.action
Land.action
RTL.action
VxFlightExec.action)

generate_messages( DEPENDENCIES uuid_msgs std_msgs nav_msgs geometry_msgs actionlib_msgs sensor_msgs shape_msgs)

set(CMAKE_CXX_FLAGS "-std=c++0x ${CMAKE_CXX_FLAGS}")

catkin_package(

CATKIN_DEPENDS
message_runtime
geometry_msgs
nav_msgs
uuid_msgs
std_msgs
sensor_msgs
shape_msgs
)

#############
## Install ##
#############
if (EXISTS include/${PROJECT_NAME})
install(DIRECTORY include/${PROJECT_NAME}
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
endif()


5 changes: 5 additions & 0 deletions brain_box_msgs/action/Fibonacci.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
int32 order
---
int32[] sequence
---
int32[] partial_sequence
4 changes: 2 additions & 2 deletions brain_box_msgs/action/VxFlightExec.action
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
# key="FP_ABORT" value="" abort currently executing flight plan
# key="FP_PAUSE" value="" pause currently executing flight plan

KeyValue command
brain_box_msgs/KeyValue command

---
# result
Expand All @@ -17,4 +17,4 @@ string result

---
#feedback
VxFlightPlanStatus status
brain_box_msgs/VxFlightPlanStatus status
2 changes: 1 addition & 1 deletion brain_box_msgs/action/WaypointNavigation.action
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Milestones
VxTrajectory trajectory
brain_box_msgs/VxTrajectory trajectory
---
bool result
---
Expand Down
2 changes: 1 addition & 1 deletion brain_box_msgs/msg/AMMap.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# A 3D AM occupancy map in binary format
Header header
std_msgs/Header header

# Resolution (in m) of the smallest octree nodes
float64 resolution
Expand Down
24 changes: 12 additions & 12 deletions brain_box_msgs/msg/BBLatency.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,15 @@ uint8 IP_ARUCO_ARUCO_IN=3
uint8 IP_ARUCO_ARUCO_OUT=4
uint8 SP_IN=0
uint8 SP_OUT=1
time capture_stamp
time transfer_stamp
time driver_stamp
time read_stamp
time image_pipeline_stamp0
time image_pipeline_stamp1
time image_pipeline_stamp2
time image_pipeline_stamp3
time image_pipeline_stamp4
time smart_pilot_stamp0
time smart_pilot_stamp1
time mavros_stamp
builtin_interfaces/Time capture_stamp
builtin_interfaces/Time transfer_stamp
builtin_interfaces/Time driver_stamp
builtin_interfaces/Time read_stamp
builtin_interfaces/Time image_pipeline_stamp0
builtin_interfaces/Time image_pipeline_stamp1
builtin_interfaces/Time image_pipeline_stamp2
builtin_interfaces/Time image_pipeline_stamp3
builtin_interfaces/Time image_pipeline_stamp4
builtin_interfaces/Time smart_pilot_stamp0
builtin_interfaces/Time smart_pilot_stamp1
builtin_interfaces/Time mavros_stamp
4 changes: 2 additions & 2 deletions brain_box_msgs/msg/BBVxCommand.msg
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ uint8 FOR_TARGET=0
uint8 FOR_GLOBAL=1
uint8 FOR_VEHICLE=2

Header header
std_msgs/Header header
uint8 command
string target_id
uint8 frame_of_reference
VxKinematics kinematics
brain_box_msgs/VxKinematics kinematics
4 changes: 2 additions & 2 deletions brain_box_msgs/msg/BabySitterStatus.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
Header header
std_msgs/Header header
string name
uint16 freq
MaxMinAve max_min_ave
brain_box_msgs/MaxMinAve max_min_ave
4 changes: 2 additions & 2 deletions brain_box_msgs/msg/BeaconRangeMsg.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
# id

std_msgs/Header header
geometry_msgs/Point beaconPosition
std_msgs/Bool isLos
geometry_msgs/Point beacon_position
std_msgs/Bool is_los
std_msgs/Float32 range
std_msgs/Float32 std
std_msgs/Float32 bias
Expand Down
2 changes: 1 addition & 1 deletion brain_box_msgs/msg/BlinkMCommand.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
# rgb: red, green and blue
# blink_rate: blinking rate, one cycle on and one cycle off

RGB rgb
brain_box_msgs/RGB rgb
float64 blink_rate
2 changes: 1 addition & 1 deletion brain_box_msgs/msg/BoundingBox.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
string Class
string class_name
string camera
int64 img_width
int64 img_height
Expand Down
6 changes: 3 additions & 3 deletions brain_box_msgs/msg/BoundingBoxes.msg
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
Header header
Header image_header
BoundingBox[] bounding_boxes
std_msgs/Header header
std_msgs/Header image_header
brain_box_msgs/BoundingBox[] bounding_boxes
4 changes: 2 additions & 2 deletions brain_box_msgs/msg/C2Status.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Header header
Status status
std_msgs/Header header
brain_box_msgs/Status status
uint32 opens
uint32 failures
uint32 timeouts
Expand Down
2 changes: 1 addition & 1 deletion brain_box_msgs/msg/CeilingHist.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
Header header
std_msgs/Header header
float32 resolution_m
float32 min_x_m
float32 max_x_m
Expand Down
4 changes: 2 additions & 2 deletions brain_box_msgs/msg/CeilingStatus.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Header header
Status status
std_msgs/Header header
brain_box_msgs/Status status
uint16 fps
uint16 process_time_ms
uint16 latency_ms
Expand Down
16 changes: 8 additions & 8 deletions brain_box_msgs/msg/Collision.msg
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
Header header
std_msgs/Header header
float32 down_m
float32 front_m
float32 right_m
float32 back_m
float32 left_m
float32 up_m
float32[3] motion_m
uint8 downHealth
uint8 frontHealth
uint8 rightHealth
uint8 backHealth
uint8 leftHealth
uint8 upHealth
uint8 motionHealth
uint8 down_health
uint8 front_health
uint8 right_health
uint8 back_health
uint8 left_health
uint8 up_health
uint8 motion_health
5 changes: 2 additions & 3 deletions brain_box_msgs/msg/CollisionViews.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Collection of collisions views
# The frame in the header should be body_FLU
Header header

CollisionView[] views
std_msgs/Header header

brain_box_msgs/CollisionView[] views
Loading