Skip to content

Commit

Permalink
Merge branch 'master' into maint/hybridize_delphi_srr
Browse files Browse the repository at this point in the history
  • Loading branch information
Joshua Whitley committed Nov 18, 2019
2 parents 07af785 + 992e2f9 commit 24cce18
Show file tree
Hide file tree
Showing 72 changed files with 628 additions and 385 deletions.
4 changes: 2 additions & 2 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -74,13 +74,13 @@ jobs:
command: |
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
cd ..
colcon build --packages-up-to delphi_esr_msgs delphi_mrr_msgs delphi_srr_msgs
colcon build --packages-skip astuff_sensor_msgs neobotix_usboard_msgs pacmod_msgs
- run:
name: Run Tests
command: |
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
cd ..
colcon test --packages-up-to delphi_esr_msgs delphi_mrr_msgs delphi_srr_msgs
colcon build --packages-skip astuff_sensor_msgs neobotix_usboard_msgs pacmod_msgs
colcon test-result
working_directory: ~/src

Expand Down
127 changes: 93 additions & 34 deletions derived_object_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,40 +1,99 @@
cmake_minimum_required(VERSION 2.8.3)
project(derived_object_msgs)

find_package(catkin REQUIRED
COMPONENTS
message_generation
std_msgs
geometry_msgs
shape_msgs
radar_msgs
)
set(ROS_VERSION $ENV{ROS_VERSION})

## Declare ROS messages and services
add_message_files(DIRECTORY msg FILES
CipvTrack.msg
LaneModels.msg
Lane.msg
ObjectArray.msg
Object.msg
ObjectWithCovarianceArray.msg
ObjectWithCovariance.msg
SolidPrimitiveWithCovariance.msg
set(MSG_FILES
"CipvTrack.msg"
"Lane.msg"
"LaneModels.msg"
"Object.msg"
"ObjectArray.msg"
"ObjectWithCovariance.msg"
"ObjectWithCovarianceArray.msg"
"SolidPrimitiveWithCovariance.msg"
)

## Generate added messages and services
generate_messages(DEPENDENCIES
std_msgs
geometry_msgs
shape_msgs
radar_msgs
)
if(${ROS_VERSION} EQUAL 1)

## Declare a catkin package
catkin_package(CATKIN_DEPENDS
message_runtime
std_msgs
geometry_msgs
shape_msgs
radar_msgs
)
cmake_minimum_required(VERSION 2.8.3)

# Default to C++11
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 11)
endif()

find_package(catkin REQUIRED
COMPONENTS
geometry_msgs
message_generation
radar_msgs
shape_msgs
std_msgs
)

add_message_files(FILES
${MSG_FILES}
DIRECTORY msg
)

generate_messages(
DEPENDENCIES
geometry_msgs
radar_msgs
shape_msgs
std_msgs
)

catkin_package(
CATKIN_DEPENDS message_runtime
)

elseif(${ROS_VERSION} EQUAL 2)

cmake_minimum_required(VERSION 3.5)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(radar_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(shape_msgs REQUIRED)
find_package(std_msgs REQUIRED)

# Apend "msg/" to each file name
set(TEMP_LIST "")
foreach(MSG_FILE ${MSG_FILES})
list(APPEND TEMP_LIST "msg/${MSG_FILE}")
endforeach()
set(MSG_FILES ${TEMP_LIST})

rosidl_generate_interfaces(${PROJECT_NAME}
${MSG_FILES}
DEPENDENCIES
builtin_interfaces
geometry_msgs
shape_msgs
std_msgs
radar_msgs
ADD_LINTER_TESTS
)

ament_export_dependencies(rosidl_default_runtime)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()

endif()
3 changes: 0 additions & 3 deletions derived_object_msgs/msg/Lane.msg
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,5 @@ float64 marker_offset # Lateral distance from sensor to marker (m)
float64 heading_angle # Angle of marker relative to sensor (rad)
float64 curvature # Curvature of the lane marker at the camera (1/m)
float64 curvature_derivative # Amount curvature changes as you move away from the camera (1/m^2)

float64 marker_width # Width of the painted marker (not distance between lane markers) (m)

float64 view_range # Physical view range of the lane mark (m)

4 changes: 1 addition & 3 deletions derived_object_msgs/msg/Object.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# This represents a detected or tracked object with reference coordinate frame and timestamp.

Header header
std_msgs/Header header

# The id of the object (presumably from the detecting sensor).
uint32 id
Expand All @@ -10,7 +10,6 @@ uint32 id
# An object which is detected can only be assumed to have valid pose and shape properties.
# An object which is tracked should also be assumed to have valid twist and accel properties.
uint8 detection_level

uint8 OBJECT_DETECTED=0
uint8 OBJECT_TRACKED=1

Expand All @@ -35,7 +34,6 @@ shape_msgs/SolidPrimitive shape

# The type of classification given to this object.
uint8 classification

uint8 CLASSIFICATION_UNKNOWN=0
uint8 CLASSIFICATION_UNKNOWN_SMALL=1
uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2
Expand Down
4 changes: 2 additions & 2 deletions derived_object_msgs/msg/ObjectArray.msg
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
Header header
std_msgs/Header header

Object[] objects
derived_object_msgs/Object[] objects
4 changes: 1 addition & 3 deletions derived_object_msgs/msg/ObjectWithCovariance.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# This represents an estimated object with reference coordinate frame and timestamp.
Header header
std_msgs/Header header

# The id of the object (presumably from the detecting sensor).
uint32 id
Expand All @@ -10,7 +10,6 @@ uint32 id
# An object which is tracked should also be assumed to have valid twist and accel properties.
# The validity of the individual components of each object property are defined by the property's covariance matrix.
uint8 detection_level

uint8 OBJECT_DETECTED=0
uint8 OBJECT_TRACKED=1

Expand All @@ -35,7 +34,6 @@ derived_object_msgs/SolidPrimitiveWithCovariance shape

# The type of classification given to this object.
uint8 classification

uint8 CLASSIFICATION_UNKNOWN=0
uint8 CLASSIFICATION_UNKNOWN_SMALL=1
uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2
Expand Down
2 changes: 1 addition & 1 deletion derived_object_msgs/msg/ObjectWithCovarianceArray.msg
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
Header header
std_msgs/Header header

derived_object_msgs/ObjectWithCovariance[] objects
11 changes: 2 additions & 9 deletions derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,47 +2,40 @@
# All shapes are defined to have their bounding boxes centered around 0,0,0.
# This message based on shape_msgs/SolidPrimitive

# The type of the shape
uint8 type
uint8 BOX=1
uint8 SPHERE=2
uint8 CYLINDER=3
uint8 CONE=4

# The type of the shape
uint8 type


# The dimensions of the shape
float64[] dimensions

# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array

# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding
# sides of the box.
uint8 BOX_X=0
uint8 BOX_Y=1
uint8 BOX_Z=2


# For the SPHERE type, only one component is used, and it gives the radius of
# the sphere.
uint8 SPHERE_RADIUS=0


# For the CYLINDER and CONE types, the center line is oriented along
# the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component
# of dimensions gives the height of the cylinder (cone). The
# CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the
# radius of the base of the cylinder (cone). Cone and cylinder
# primitives are defined to be circular. The tip of the cone is
# pointing up, along +Z axis.

uint8 CYLINDER_HEIGHT=0
uint8 CYLINDER_RADIUS=1

uint8 CONE_HEIGHT=0
uint8 CONE_RADIUS=1


# Row-major representation of the covariance matrix associated with the shape.
# For the BOX type, this should be a 3x3 matrix defining the uncertainty of the X, Y, and Z measurements.
# For the SPHERE type, this should contain only one value for the radius.
Expand Down
Loading

0 comments on commit 24cce18

Please sign in to comment.