Skip to content

Commit

Permalink
Merge branch 'main' into refactor/image_transport_decompressor
Browse files Browse the repository at this point in the history
  • Loading branch information
knzo25 authored May 17, 2024
2 parents 443f823 + 0518585 commit f033363
Show file tree
Hide file tree
Showing 502 changed files with 93,588 additions and 5,842 deletions.
38 changes: 22 additions & 16 deletions .github/CODEOWNERS

Large diffs are not rendered by default.

4 changes: 4 additions & 0 deletions .github/PULL_REQUEST_TEMPLATE/small-change.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@ Not applicable.

Not applicable.

## Interface changes

<!-- Describe any changed interfaces, such as topics, services, or parameters, including debugging interfaces -->

## Pre-review checklist for the PR author

The PR author **must** check the checkboxes below when creating the PR.
Expand Down
13 changes: 13 additions & 0 deletions .github/PULL_REQUEST_TEMPLATE/standard-change.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,19 @@

<!-- Describe any changed interfaces, such as topics, services, or parameters. -->

### ROS Topic Changes

<!-- | Topic Name | Type | Direction | Update Description | -->
<!-- | ---------------- | ------------------- | --------- | ------------------------------------------------------------- | -->
<!-- | `/example_topic` | `std_msgs/String` | Subscribe | Description of what the topic is used for in the system | -->
<!-- | `/another_topic` | `sensor_msgs/Image` | Publish | Also explain if it is added / modified / deleted with the PR | -->

### ROS Parameter Changes

<!-- | Parameter Name | Default Value | Update Description | -->
<!-- | -------------------- | ------------- | --------------------------------------------------- | -->
<!-- | `example_parameters` | `1.0` | Describe the parameter and also explain the updates | -->

## Effects on system behavior

<!-- Describe how this PR affects the system behavior. -->
Expand Down
4 changes: 4 additions & 0 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -41,3 +41,7 @@ repositories:
type: git
url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git
version: main
universe/external/glog: # TODO: to use isGoogleInitialized() API in v0.6.0. Remove when the rosdep glog version is updated to v0.6.0 (already updated in Ubuntu 24.04)
type: git
url: https://github.com/tier4/glog.git
version: v0.6.0_t4-ros
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,9 @@ namespace types
// We don't currently require code to comply to MISRA, but we should try to where it is
// easily possible.
using bool8_t = bool;
#if __cplusplus < 201811L || !__cpp_char8_t
using char8_t = char;
#endif
using uchar8_t = unsigned char;
// If we ever compile on a platform where this is not true, float32_t and float64_t definitions
// need to be adjusted.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,9 @@ struct ObjectPropertyValues
float alpha{0.999F};
};

// Control object marker visualization
enum class ObjectFillType { Skeleton, Fill };

// Map defining colors according to value of label field in ObjectClassification msg
const std::map<
autoware_auto_perception_msgs::msg::ObjectClassification::_label_type, ObjectPropertyValues>
Expand Down Expand Up @@ -87,7 +90,8 @@ get_shape_marker_ptr(
const autoware_auto_perception_msgs::msg::Shape & shape_msg,
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width,
const bool & is_orientation_available = true);
const bool & is_orientation_available = true,
const ObjectFillType fill_type = ObjectFillType::Skeleton);

AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr
get_2d_shape_marker_ptr(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,12 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
m_confidence_interval_property->addOption("95%", 2);
m_confidence_interval_property->addOption("99%", 3);

m_object_fill_type_property = new rviz_common::properties::EnumProperty(
"Object Fill Type", "skeleton", "Change object fill type in visualization", this);
m_object_fill_type_property->addOption(
"skeleton", static_cast<int>(detail::ObjectFillType::Skeleton));
m_object_fill_type_property->addOption("Fill", static_cast<int>(detail::ObjectFillType::Fill));

// iterate over default values to create and initialize the properties.
for (const auto & map_property_it : detail::kDefaultObjectPropertyValues) {
const auto & class_property_values = map_property_it.second;
Expand Down Expand Up @@ -189,9 +195,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
const bool & is_orientation_available) const
{
const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels);
const auto fill_type =
static_cast<detail::ObjectFillType>(m_object_fill_type_property->getOptionInt());

if (m_display_type_property->getOptionInt() == 0) {
return detail::get_shape_marker_ptr(
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available);
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available,
fill_type);
} else if (m_display_type_property->getOptionInt() == 1) {
return detail::get_2d_shape_marker_ptr(
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available);
Expand Down Expand Up @@ -526,6 +536,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
rviz_common::properties::EnumProperty * m_simple_visualize_mode_property;
// Property to set confidence interval of state estimations
rviz_common::properties::EnumProperty * m_confidence_interval_property;
// Property to set visualization type
rviz_common::properties::EnumProperty * m_object_fill_type_property;
// Property to enable/disable label visualization
rviz_common::properties::BoolProperty m_display_label_property;
// Property to enable/disable uuid visualization
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -495,23 +495,37 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
const autoware_auto_perception_msgs::msg::Shape & shape_msg,
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width,
const bool & is_orientation_available)
const bool & is_orientation_available, const ObjectFillType fill_type)
{
auto marker_ptr = std::make_shared<Marker>();
marker_ptr->ns = std::string("shape");
marker_ptr->color = color_rgba;
marker_ptr->scale.x = line_width;

using autoware_auto_perception_msgs::msg::Shape;
if (shape_msg.type == Shape::BOUNDING_BOX) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
calc_bounding_box_line_list(shape_msg, marker_ptr->points);
if (fill_type == ObjectFillType::Skeleton) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
calc_bounding_box_line_list(shape_msg, marker_ptr->points);
} else if (fill_type == ObjectFillType::Fill) {
marker_ptr->type = visualization_msgs::msg::Marker::CUBE;
marker_ptr->scale = shape_msg.dimensions;
marker_ptr->color.a = 0.75f;
}
if (is_orientation_available) {
calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points);
} else {
calc_bounding_box_orientation_line_list(shape_msg, marker_ptr->points);
}
} else if (shape_msg.type == Shape::CYLINDER) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
calc_cylinder_line_list(shape_msg, marker_ptr->points);
if (fill_type == ObjectFillType::Skeleton) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
calc_cylinder_line_list(shape_msg, marker_ptr->points);
} else if (fill_type == ObjectFillType::Fill) {
marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER;
marker_ptr->scale = shape_msg.dimensions;
marker_ptr->color.a = 0.75f;
}
} else if (shape_msg.type == Shape::POLYGON) {
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
calc_polygon_line_list(shape_msg, marker_ptr->points);
Expand All @@ -523,8 +537,6 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
marker_ptr->pose = to_pose(centroid, orientation);
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);
marker_ptr->scale.x = line_width;
marker_ptr->color = color_rgba;

return marker_ptr;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
cmake_minimum_required(VERSION 3.8)
project(autoware_mission_details_overlay_rviz_plugin)

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

set(
headers_to_moc
include/mission_details_display.hpp
)

set(
headers_to_not_moc
include/remaining_distance_time_display.hpp
)

foreach(header "${headers_to_moc}")
qt5_wrap_cpp(display_moc_files "${header}")
endforeach()

set(
display_source_files
src/overlay_utils.cpp
src/mission_details_display.cpp
src/remaining_distance_time_display.cpp
)

add_library(
${PROJECT_NAME} SHARED
${display_moc_files}
${headers_to_not_moc}
${display_source_files}
)

set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17)
target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic)

target_include_directories(
${PROJECT_NAME} PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${Qt5Widgets_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)

target_link_libraries(
${PROJECT_NAME} PUBLIC
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay
)

target_compile_definitions(${PROJECT_NAME} PRIVATE "${PROJECT_NAME}_BUILDING_LIBRARY")

# prevent pluginlib from using boost
target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")

pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)

ament_target_dependencies(
${PROJECT_NAME}
PUBLIC
rviz_common
rviz_rendering
autoware_internal_msgs
)

ament_export_include_directories(include)
ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(
rviz_common
rviz_ogre_vendor
)

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

install(
TARGETS ${PROJECT_NAME}
EXPORT ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)

install(
DIRECTORY include/
DESTINATION include
)

install(
TARGETS
DESTINATION lib/${PROJECT_NAME}
)

# Copy the assets directory to the installation directory
install(
DIRECTORY assets/
DESTINATION share/${PROJECT_NAME}/assets
)

add_definitions(-DQT_NO_KEYWORDS)

ament_package(
CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake"
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
Copyright (c) 2022, Team Spatzenhirn
Copyright (c) 2014, JSK Lab

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
# autoware_mission_details_overlay_rviz_plugin

This RViz plugin displays the remaining distance and time for the current mission.

## Inputs / Outputs

### Input

| Name | Type | Description |
| ------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------- |
| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time |

## Overlay Parameters

| Name | Type | Default Value | Description |
| -------- | ---- | ------------- | --------------------------------- |
| `Width` | int | 170 | Width of the overlay [px] |
| `Height` | int | 100 | Height of the overlay [px] |
| `Right` | int | 10 | Margin from the right border [px] |
| `Top` | int | 10 | Margin from the top border [px] |

The mission details display is aligned with top right corner of the screen.

## Usage

Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README.md)

## Credits

Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) package.

### Icons

- <https://fonts.google.com/icons?selected=Material+Symbols+Outlined:conversion_path:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=path>
- <https://fonts.google.com/icons?selected=Material+Symbols+Outlined:av_timer:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=av+timer>
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading

0 comments on commit f033363

Please sign in to comment.