Skip to content

Commit

Permalink
Merge pull request #32 from sloretz/sync_with_kinetic
Browse files Browse the repository at this point in the history
Sync ros2 with master
  • Loading branch information
Kukanani authored Oct 7, 2019
2 parents 80802c3 + 7928732 commit d4adeef
Show file tree
Hide file tree
Showing 15 changed files with 117 additions and 36 deletions.
15 changes: 14 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,21 @@ if (BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)

ament_lint_auto_find_test_dependencies()

ament_add_gtest(vision_msgs_test test/main.cpp)
add_dependencies(vision_msgs_test ${PROJECT_NAME})
ament_target_dependencies(vision_msgs_test
geometry_msgs
std_msgs
sensor_msgs
)
# TODO(sloretz) rosidl_generate_interfaces() should make using generated messages in same project simpler
target_include_directories(vision_msgs_test PUBLIC
include
${CMAKE_CURRENT_BINARY_DIR}/rosidl_generator_cpp
)
endif()

ament_export_dependencies(rosidl_default_runtime)
ament_export_include_directories(include)
ament_package()
ament_package()
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# ROS Vision Messages Proposal
# ROS Vision Messages

## Introduction

Expand Down
2 changes: 1 addition & 1 deletion include/vision_msgs/create_aabb.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,4 +66,4 @@ namespace vision_msgs
}
}

#endif
#endif
4 changes: 2 additions & 2 deletions msg/BoundingBox2D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
# The 2D position (in pixels) and orientation of the bounding box center.
geometry_msgs/Pose2D center

# The size (in pixels) of the bounding box surrounding the object relative
# to the pose of its center.
# The size (in pixels) of the bounding box surrounding the object relative
# to the pose of its center.
float64 size_x
float64 size_y
3 changes: 2 additions & 1 deletion msg/BoundingBox3D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,6 @@
# The 3D position and orientation of the bounding box center
geometry_msgs/Pose center

# The size of the bounding box, in meters, surrounding the object's center pose.
# The size of the bounding box, in meters, surrounding the object's center
# pose.
geometry_msgs/Vector3 size
2 changes: 2 additions & 0 deletions msg/BoundingBox3DArray.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
std_msgs/Header header
vision_msgs/BoundingBox3D[] boxes
7 changes: 4 additions & 3 deletions msg/Classification2D.msg
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
# Defines a 2D classification result.
#
# This result does not contain any position information. It is designed for
# classifiers, which simply provide class probabilities given a source image.
# classifiers, which simply provide class probabilities given a source image.

std_msgs/Header header

# A list of class probabilities. This list need not provide a probability for
# every possible class, just ones that are nonzero, or above some user-defined
# every possible class, just ones that are nonzero, or above some
# user-defined threshold.
ObjectHypothesis[] results

# The 2D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all use cases, so it may be empty.
# the image). Not required for all use cases, so it may be empty.
sensor_msgs/Image source_img
4 changes: 2 additions & 2 deletions msg/Classification3D.msg
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
# Defines a 3D classification result.
#
# This result does not contain any position information. It is designed for
# classifiers, which simply provide probabilities given a source image.
# classifiers, which simply provide probabilities given a source image.

std_msgs/Header header

# Class probabilities
ObjectHypothesis[] results

# The 3D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all detectors, so it may be empty.
# the image). Not required for all detectors, so it may be empty.
sensor_msgs/PointCloud2 source_cloud
8 changes: 8 additions & 0 deletions msg/Detection2D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,11 @@ BoundingBox2D bbox
# The 2D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all use cases, so it may be empty.
sensor_msgs/Image source_img

# If true, this message contains object tracking information.
bool is_tracking

# ID used for consistency across multiple detection messages. This value will
# likely differ from the id field set in each individual ObjectHypothesis.
# If you set this field, be sure to also set is_tracking to True.
string tracking_id
12 changes: 10 additions & 2 deletions msg/Detection3D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,14 @@ ObjectHypothesisWithPose[] results
BoundingBox3D bbox

# The 3D data that generated these results (i.e. region proposal cropped out of
# the image). This information is not required for all detectors, so it may be
# empty.
# the image). This information is not required for all detectors, so it may
# be empty.
sensor_msgs/PointCloud2 source_cloud

# If this message was tracking result, this field set true.
bool is_tracking

# ID used for consistency across multiple detection messages. This value will
# likely differ from the id field set in each individual ObjectHypothesis.
# If you set this field, be sure to also set is_tracking to True.
string tracking_id
8 changes: 4 additions & 4 deletions msg/ObjectHypothesis.msg
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
# An object hypothesis that contains no position information.

# The unique numeric ID of object detected. To get additional information about
# this ID, such as its human-readable name, listeners should perform a lookup
# in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
int64 id
# The unique ID of the object class. To get additional information about
# this ID, such as its human-readable class name, listeners should perform a
# lookup in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
string id

# The probability or confidence value of the detected object. By convention,
# this value should lie in the range [0-1].
Expand Down
25 changes: 13 additions & 12 deletions msg/ObjectHypothesisWithPose.msg
Original file line number Diff line number Diff line change
@@ -1,19 +1,20 @@
# An object hypothesis that contains position information.

# The unique numeric ID of object detected. To get additional information about
# this ID, such as its human-readable name, listeners should perform a lookup
# in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
int64 id
# The unique ID of the object class. To get additional information about
# this ID, such as its human-readable class name, listeners should perform a
# lookup in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
string id

# The probability or confidence value of the detected object. By convention,
# this value should lie in the range [0-1].
float64 score

# the 6D pose of the object hypothesis. This pose should be
# defined as the pose of some fixed reference point on the object, such as the
# geometric center of the bounding box or the center of mass of the object.
# Note that this pose is not stamped; frame information can be defined by parent
# messages.
# Also note that different classes predicted
# for the same input data may have different predicted 6D poses.
geometry_msgs/Pose pose
# The 6D pose of the object hypothesis. This pose should be
# defined as the pose of some fixed reference point on the object, such a
# the geometric center of the bounding box or the center of mass of the
# object.
# Note that this pose is not stamped; frame information can be defined by
# parent messages.
# Also note that different classes predicted for the same input data may have
# different predicted 6D poses.
geometry_msgs/PoseWithCovariance pose
14 changes: 7 additions & 7 deletions msg/VisionInfo.msg
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ string method
# Location where the metadata database is stored. The recommended location is
# as an XML string on the ROS parameter server, but the exact implementation
# and information is left up to the user.
# The database should store information attached to numeric ids. Each
# numeric id should map to an atomic, visually recognizable element. This
# definition is intentionally vague to allow extreme flexibility. The elements
# could be classes in a pixel segmentation algorithm, object classes in a
# detector, different people's faces in a face detection algorithm, etc.
# Vision pipelines report results in terms of numeric IDs, which map into this
# database.
# The database should store information attached to class ids. Each
# class id should map to an atomic, visually recognizable element. This
# definition is intentionally vague to allow extreme flexibility. The
# elements could be classes in a pixel segmentation algorithm, object classes
# in a detector, different people's faces in a face detection algorithm, etc.
# Vision pipelines report results in terms of numeric IDs, which map into
# this database.
# The information stored in this database is, again, left up to the user. The
# database could be as simple as a map from ID to class name, or it could
# include information such as object meshes or colors to use for
Expand Down
3 changes: 3 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
<license>Apache License 2.0</license>

<author email="adam.d.allevato@gmail.com">Adam Allevato</author>
<maintainer email="adam.d.allevato@gmail.com">Adam Allevato</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
Expand All @@ -25,6 +27,7 @@
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

Expand Down
44 changes: 44 additions & 0 deletions test/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include "vision_msgs/msg/bounding_box2_d.hpp"
#include "vision_msgs/msg/bounding_box3_d.hpp"
#include "vision_msgs/create_aabb.h"

TEST(vision_msgs, CreateAABB2D)
{
vision_msgs::msg::BoundingBox2D bbox = vision_msgs::createAABB2D(1,2,3,4);
EXPECT_FLOAT_EQ(bbox.center.x, 2.5); // 1 + 3/2
EXPECT_FLOAT_EQ(bbox.center.y, 4); // 2 + 4/2
EXPECT_EQ(bbox.size_x, 3);
EXPECT_EQ(bbox.size_y, 4);
EXPECT_EQ(bbox.center.theta, 0);
}

TEST(vision_msgs, CreateAABB3D)
{
vision_msgs::msg::BoundingBox3D bbox = vision_msgs::createAABB3D(1,2,3,4,5,6);
EXPECT_FLOAT_EQ(bbox.center.position.x, 3); // 1 + 4/2
EXPECT_FLOAT_EQ(bbox.center.position.y, 4.5); // 2 + 5/2
EXPECT_FLOAT_EQ(bbox.center.position.z, 6); // 3 + 6/2
EXPECT_EQ(bbox.center.orientation.x, 0);
EXPECT_EQ(bbox.center.orientation.y, 0);
EXPECT_EQ(bbox.center.orientation.z, 0);
EXPECT_EQ(bbox.center.orientation.w, 1);
EXPECT_EQ(bbox.size.x, 4);
EXPECT_EQ(bbox.size.y, 5);
EXPECT_EQ(bbox.size.z, 6);
}

0 comments on commit d4adeef

Please sign in to comment.