Skip to content

Commit

Permalink
fix(dummy_perception_publisher, tier4_dummy_object_rviz_plugin): sepa…
Browse files Browse the repository at this point in the history
…rate dummy object msg (autowarefoundation#8828)

* fix: dummy object rviz plugin dependency

Signed-off-by: Taekjin LEE <[email protected]>

* fix: remove message from dummy perception publisher

Signed-off-by: Taekjin LEE <[email protected]>

* fix: node name

Signed-off-by: Taekjin LEE <[email protected]>

---------

Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin authored Sep 12, 2024
1 parent 1322e0c commit 69d3176
Show file tree
Hide file tree
Showing 19 changed files with 55 additions and 91 deletions.
16 changes: 0 additions & 16 deletions simulator/dummy_perception_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,6 @@ project(dummy_perception_publisher)
find_package(autoware_cmake REQUIRED)
autoware_package()

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/InitialState.msg"
"msg/Object.msg"
DEPENDENCIES autoware_perception_msgs tier4_perception_msgs geometry_msgs std_msgs unique_identifier_msgs
)

# See ndt_omp package for documentation on why PCL is special
find_package(PCL REQUIRED COMPONENTS common filters)

Expand Down Expand Up @@ -46,16 +40,6 @@ target_include_directories(dummy_perception_publisher_node
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)

# For using message definitions from the same package
if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
rosidl_target_interfaces(dummy_perception_publisher_node
${PROJECT_NAME} "rosidl_typesupport_cpp")
else()
rosidl_get_typesupport_target(
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(dummy_perception_publisher_node "${cpp_typesupport_target}")
endif()

# PCL dependencies - `ament_target_dependencies` doesn't respect the
# components/modules selected above and only links in `common` ,so we need
# to do this manually.
Expand Down
2 changes: 1 addition & 1 deletion simulator/dummy_perception_publisher/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ This node publishes the result of the dummy detection with the type of perceptio
| Name | Type | Description |
| -------------- | ----------------------------------------- | ----------------------- |
| `/tf` | `tf2_msgs/TFMessage` | TF (self-pose) |
| `input/object` | `dummy_perception_publisher::msg::Object` | dummy detection objects |
| `input/object` | `tier4_simulation_msgs::msg::DummyObject` | dummy detection objects |

### Output

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,13 @@
#ifndef DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_
#define DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_

#include "dummy_perception_publisher/msg/object.hpp"

#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
#include <tier4_simulation_msgs/msg/dummy_object.hpp>

#include <pcl/common/distances.h>
#include <pcl/point_types.h>
Expand All @@ -45,7 +44,7 @@
struct ObjectInfo
{
ObjectInfo(
const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time);
const tier4_simulation_msgs::msg::DummyObject & object, const rclcpp::Time & current_time);
double length;
double width;
double height;
Expand All @@ -60,7 +59,7 @@ struct ObjectInfo
// convert to TrackedObject
// (todo) currently need object input to get id and header information, but it should be removed
autoware_perception_msgs::msg::TrackedObject toTrackedObject(
const dummy_perception_publisher::msg::Object & object) const;
const tier4_simulation_msgs::msg::DummyObject & object) const;
};

class PointCloudCreator
Expand Down Expand Up @@ -116,11 +115,11 @@ class DummyPerceptionPublisherNode : public rclcpp::Node
detected_object_with_feature_pub_;
rclcpp::Publisher<autoware_perception_msgs::msg::TrackedObjects>::SharedPtr
ground_truth_objects_pub_;
rclcpp::Subscription<dummy_perception_publisher::msg::Object>::SharedPtr object_sub_;
rclcpp::Subscription<tier4_simulation_msgs::msg::DummyObject>::SharedPtr object_sub_;
rclcpp::TimerBase::SharedPtr timer_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
std::vector<dummy_perception_publisher::msg::Object> objects_;
std::vector<tier4_simulation_msgs::msg::DummyObject> objects_;
double visible_range_;
double detection_successful_rate_;
bool enable_ray_tracing_;
Expand All @@ -134,7 +133,7 @@ class DummyPerceptionPublisherNode : public rclcpp::Node

std::mt19937 random_generator_;
void timerCallback();
void objectCallback(const dummy_perception_publisher::msg::Object::ConstSharedPtr msg);
void objectCallback(const tier4_simulation_msgs::msg::DummyObject::ConstSharedPtr msg);

public:
DummyPerceptionPublisherNode();
Expand Down
3 changes: 0 additions & 3 deletions simulator/dummy_perception_publisher/msg/InitialState.msg

This file was deleted.

13 changes: 0 additions & 13 deletions simulator/dummy_perception_publisher/msg/Object.msg

This file was deleted.

5 changes: 1 addition & 4 deletions simulator/dummy_perception_publisher/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

<depend>autoware_perception_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
Expand All @@ -30,9 +29,7 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_perception_msgs</depend>
<depend>unique_identifier_msgs</depend>

<member_of_group>rosidl_interface_packages</member_of_group>
<depend>tier4_simulation_msgs</depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
20 changes: 10 additions & 10 deletions simulator/dummy_perception_publisher/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ using autoware_perception_msgs::msg::TrackedObject;
using autoware_perception_msgs::msg::TrackedObjects;

ObjectInfo::ObjectInfo(
const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time)
const tier4_simulation_msgs::msg::DummyObject & object, const rclcpp::Time & current_time)
: length(object.shape.dimensions.x),
width(object.shape.dimensions.y),
height(object.shape.dimensions.z),
Expand Down Expand Up @@ -108,7 +108,7 @@ ObjectInfo::ObjectInfo(
}

TrackedObject ObjectInfo::toTrackedObject(
const dummy_perception_publisher::msg::Object & object) const
const tier4_simulation_msgs::msg::DummyObject & object) const
{
TrackedObject tracked_object;
tracked_object.kinematics.pose_with_covariance = pose_covariance_;
Expand Down Expand Up @@ -164,7 +164,7 @@ DummyPerceptionPublisherNode::DummyPerceptionPublisherNode()
this->create_publisher<tier4_perception_msgs::msg::DetectedObjectsWithFeature>(
"output/dynamic_object", qos);
pointcloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("output/points_raw", qos);
object_sub_ = this->create_subscription<dummy_perception_publisher::msg::Object>(
object_sub_ = this->create_subscription<tier4_simulation_msgs::msg::DummyObject>(
"input/object", 100,
std::bind(&DummyPerceptionPublisherNode::objectCallback, this, std::placeholders::_1));

Expand Down Expand Up @@ -331,10 +331,10 @@ void DummyPerceptionPublisherNode::timerCallback()
}

void DummyPerceptionPublisherNode::objectCallback(
const dummy_perception_publisher::msg::Object::ConstSharedPtr msg)
const tier4_simulation_msgs::msg::DummyObject::ConstSharedPtr msg)
{
switch (msg->action) {
case dummy_perception_publisher::msg::Object::ADD: {
case tier4_simulation_msgs::msg::DummyObject::ADD: {
tf2::Transform tf_input2map;
tf2::Transform tf_input2object_origin;
tf2::Transform tf_map2object_origin;
Expand All @@ -350,7 +350,7 @@ void DummyPerceptionPublisherNode::objectCallback(
}
tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin);
tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin;
dummy_perception_publisher::msg::Object object;
tier4_simulation_msgs::msg::DummyObject object;
object = *msg;
tf2::toMsg(tf_map2object_origin, object.initial_state.pose_covariance.pose);

Expand All @@ -371,7 +371,7 @@ void DummyPerceptionPublisherNode::objectCallback(
objects_.push_back(object);
break;
}
case dummy_perception_publisher::msg::Object::DELETE: {
case tier4_simulation_msgs::msg::DummyObject::DELETE: {
for (size_t i = 0; i < objects_.size(); ++i) {
if (objects_.at(i).id.uuid == msg->id.uuid) {
objects_.erase(objects_.begin() + i);
Expand All @@ -380,7 +380,7 @@ void DummyPerceptionPublisherNode::objectCallback(
}
break;
}
case dummy_perception_publisher::msg::Object::MODIFY: {
case tier4_simulation_msgs::msg::DummyObject::MODIFY: {
for (size_t i = 0; i < objects_.size(); ++i) {
if (objects_.at(i).id.uuid == msg->id.uuid) {
tf2::Transform tf_input2map;
Expand All @@ -398,7 +398,7 @@ void DummyPerceptionPublisherNode::objectCallback(
}
tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin);
tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin;
dummy_perception_publisher::msg::Object object;
tier4_simulation_msgs::msg::DummyObject object;
objects_.at(i) = *msg;
tf2::toMsg(tf_map2object_origin, objects_.at(i).initial_state.pose_covariance.pose);
if (use_base_link_z_) {
Expand All @@ -420,7 +420,7 @@ void DummyPerceptionPublisherNode::objectCallback(
}
break;
}
case dummy_perception_publisher::msg::Object::DELETEALL: {
case tier4_simulation_msgs::msg::DummyObject::DELETEALL: {
objects_.clear();
break;
}
Expand Down
2 changes: 1 addition & 1 deletion simulator/tier4_dummy_object_rviz_plugin/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ The DeleteAllObjectsTool deletes the dummy cars, pedestrians, and obstacles disp

| Name | Type | Description |
| ---------------------------------------------------- | ----------------------------------------- | ----------------------------------------------- |
| `/simulation/dummy_perception_publisher/object_info` | `dummy_perception_publisher::msg::Object` | The topic on which to publish dummy object info |
| `/simulation/dummy_perception_publisher/object_info` | `tier4_simulation_msgs::msg::DummyObject` | The topic on which to publish dummy object info |

## Parameter

Expand Down
2 changes: 1 addition & 1 deletion simulator/tier4_dummy_object_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>dummy_perception_publisher</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
<depend>libqt5-widgets</depend>
Expand All @@ -19,6 +18,7 @@
<depend>rviz_default_plugins</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_simulation_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
12 changes: 6 additions & 6 deletions simulator/tier4_dummy_object_rviz_plugin/src/tools/car_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,9 +112,9 @@ void CarInitialPoseTool::onInitialize()
updateTopic();
}

Object CarInitialPoseTool::createObjectMsg() const
DummyObject CarInitialPoseTool::createObjectMsg() const
{
Object object{};
DummyObject object{};
std::string fixed_frame = context_->getFixedFrame().toStdString();

// header
Expand Down Expand Up @@ -205,9 +205,9 @@ void BusInitialPoseTool::onInitialize()
updateTopic();
}

Object BusInitialPoseTool::createObjectMsg() const
DummyObject BusInitialPoseTool::createObjectMsg() const
{
Object object{};
DummyObject object{};
std::string fixed_frame = context_->getFixedFrame().toStdString();

// header
Expand Down Expand Up @@ -302,9 +302,9 @@ void BikeInitialPoseTool::onInitialize()
updateTopic();
}

Object BikeInitialPoseTool::createObjectMsg() const
DummyObject BikeInitialPoseTool::createObjectMsg() const
{
Object object{};
DummyObject object{};
std::string fixed_frame = context_->getFixedFrame().toStdString();

// header
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,30 +55,30 @@ namespace rviz_plugins

using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::Shape;
using dummy_perception_publisher::msg::Object;
using tier4_simulation_msgs::msg::DummyObject;

class CarInitialPoseTool : public InteractiveObjectTool
{
public:
CarInitialPoseTool();
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
[[nodiscard]] DummyObject createObjectMsg() const override;
};

class BusInitialPoseTool : public InteractiveObjectTool
{
public:
BusInitialPoseTool();
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
[[nodiscard]] DummyObject createObjectMsg() const override;
};

class BikeInitialPoseTool : public InteractiveObjectTool
{
public:
BikeInitialPoseTool();
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
[[nodiscard]] DummyObject createObjectMsg() const override;

private:
rviz_common::properties::EnumProperty * label_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ void DeleteAllObjectsTool::onInitialize()
void DeleteAllObjectsTool::updateTopic()
{
rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node();
dummy_object_info_pub_ = raw_node->create_publisher<dummy_perception_publisher::msg::Object>(
dummy_object_info_pub_ = raw_node->create_publisher<tier4_simulation_msgs::msg::DummyObject>(
topic_property_->getStdString(), 1);
clock_ = raw_node->get_clock();
}
Expand All @@ -82,15 +82,15 @@ void DeleteAllObjectsTool::updateTopic()
void DeleteAllObjectsTool::onPoseSet(
[[maybe_unused]] double x, [[maybe_unused]] double y, [[maybe_unused]] double theta)
{
dummy_perception_publisher::msg::Object output_msg;
tier4_simulation_msgs::msg::DummyObject output_msg;
std::string fixed_frame = context_->getFixedFrame().toStdString();

// header
output_msg.header.frame_id = fixed_frame;
output_msg.header.stamp = clock_->now();

// action
output_msg.action = dummy_perception_publisher::msg::Object::DELETEALL;
output_msg.action = tier4_simulation_msgs::msg::DummyObject::DELETEALL;

dummy_object_info_pub_->publish(output_msg);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
#include <rviz_default_plugins/tools/pose/pose_tool.hpp>
#endif

#include <dummy_perception_publisher/msg/object.hpp>
#include <tier4_simulation_msgs/msg/dummy_object.hpp>

namespace rviz_plugins
{
Expand All @@ -77,7 +77,7 @@ private Q_SLOTS:

private: // NOLINT for Qt
rclcpp::Clock::SharedPtr clock_;
rclcpp::Publisher<dummy_perception_publisher::msg::Object>::SharedPtr dummy_object_info_pub_;
rclcpp::Publisher<tier4_simulation_msgs::msg::DummyObject>::SharedPtr dummy_object_info_pub_;

rviz_common::properties::StringProperty * topic_property_;
};
Expand Down
Loading

0 comments on commit 69d3176

Please sign in to comment.