Skip to content

Commit e6838dd

Browse files
committed
build(dummy_perception_publisher): fix include paths and namespaces for messages
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent bd69879 commit e6838dd

File tree

3 files changed

+20
-20
lines changed

3 files changed

+20
-20
lines changed

simulator/dummy_perception_publisher/README.md

+4-4
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,10 @@ This node publishes the result of the dummy detection with the type of perceptio
1010

1111
### Input
1212

13-
| Name | Type | Description |
14-
| -------------- | ----------------------------------------- | ----------------------- |
15-
| `/tf` | `tf2_msgs/TFMessage` | TF (self-pose) |
16-
| `input/object` | `dummy_perception_publisher::msg::Object` | dummy detection objects |
13+
| Name | Type | Description |
14+
| -------------- | -------------------------------------------------- | ----------------------- |
15+
| `/tf` | `tf2_msgs/TFMessage` | TF (self-pose) |
16+
| `input/object` | `autoware_dummy_perception_publisher::msg::Object` | dummy detection objects |
1717

1818
### Output
1919

simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_
1616
#define DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_
1717

18-
#include "dummy_perception_publisher/msg/object.hpp"
18+
#include "autoware_dummy_perception_publisher/msg/object.hpp"
1919

2020
#include <rclcpp/rclcpp.hpp>
2121

@@ -45,7 +45,7 @@
4545
struct ObjectInfo
4646
{
4747
ObjectInfo(
48-
const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time);
48+
const autoware_dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time);
4949
double length;
5050
double width;
5151
double height;
@@ -60,7 +60,7 @@ struct ObjectInfo
6060
// convert to TrackedObject
6161
// (todo) currently need object input to get id and header information, but it should be removed
6262
autoware_auto_perception_msgs::msg::TrackedObject toTrackedObject(
63-
const dummy_perception_publisher::msg::Object & object) const;
63+
const autoware_dummy_perception_publisher::msg::Object & object) const;
6464
};
6565

6666
class PointCloudCreator
@@ -116,11 +116,11 @@ class DummyPerceptionPublisherNode : public rclcpp::Node
116116
detected_object_with_feature_pub_;
117117
rclcpp::Publisher<autoware_auto_perception_msgs::msg::TrackedObjects>::SharedPtr
118118
ground_truth_objects_pub_;
119-
rclcpp::Subscription<dummy_perception_publisher::msg::Object>::SharedPtr object_sub_;
119+
rclcpp::Subscription<autoware_dummy_perception_publisher::msg::Object>::SharedPtr object_sub_;
120120
rclcpp::TimerBase::SharedPtr timer_;
121121
tf2_ros::Buffer tf_buffer_;
122122
tf2_ros::TransformListener tf_listener_;
123-
std::vector<dummy_perception_publisher::msg::Object> objects_;
123+
std::vector<autoware_dummy_perception_publisher::msg::Object> objects_;
124124
double visible_range_;
125125
double detection_successful_rate_;
126126
bool enable_ray_tracing_;
@@ -134,7 +134,7 @@ class DummyPerceptionPublisherNode : public rclcpp::Node
134134

135135
std::mt19937 random_generator_;
136136
void timerCallback();
137-
void objectCallback(const dummy_perception_publisher::msg::Object::ConstSharedPtr msg);
137+
void objectCallback(const autoware_dummy_perception_publisher::msg::Object::ConstSharedPtr msg);
138138

139139
public:
140140
DummyPerceptionPublisherNode();

simulator/dummy_perception_publisher/src/node.cpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ using autoware_auto_perception_msgs::msg::TrackedObject;
3737
using autoware_auto_perception_msgs::msg::TrackedObjects;
3838

3939
ObjectInfo::ObjectInfo(
40-
const dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time)
40+
const autoware_dummy_perception_publisher::msg::Object & object, const rclcpp::Time & current_time)
4141
: length(object.shape.dimensions.x),
4242
width(object.shape.dimensions.y),
4343
height(object.shape.dimensions.z),
@@ -108,7 +108,7 @@ ObjectInfo::ObjectInfo(
108108
}
109109

110110
TrackedObject ObjectInfo::toTrackedObject(
111-
const dummy_perception_publisher::msg::Object & object) const
111+
const autoware_dummy_perception_publisher::msg::Object & object) const
112112
{
113113
TrackedObject tracked_object;
114114
tracked_object.kinematics.pose_with_covariance = pose_covariance_;
@@ -162,7 +162,7 @@ DummyPerceptionPublisherNode::DummyPerceptionPublisherNode()
162162
this->create_publisher<tier4_perception_msgs::msg::DetectedObjectsWithFeature>(
163163
"output/dynamic_object", qos);
164164
pointcloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("output/points_raw", qos);
165-
object_sub_ = this->create_subscription<dummy_perception_publisher::msg::Object>(
165+
object_sub_ = this->create_subscription<autoware_dummy_perception_publisher::msg::Object>(
166166
"input/object", 100,
167167
std::bind(&DummyPerceptionPublisherNode::objectCallback, this, std::placeholders::_1));
168168

@@ -329,10 +329,10 @@ void DummyPerceptionPublisherNode::timerCallback()
329329
}
330330

331331
void DummyPerceptionPublisherNode::objectCallback(
332-
const dummy_perception_publisher::msg::Object::ConstSharedPtr msg)
332+
const autoware_dummy_perception_publisher::msg::Object::ConstSharedPtr msg)
333333
{
334334
switch (msg->action) {
335-
case dummy_perception_publisher::msg::Object::ADD: {
335+
case autoware_dummy_perception_publisher::msg::Object::ADD: {
336336
tf2::Transform tf_input2map;
337337
tf2::Transform tf_input2object_origin;
338338
tf2::Transform tf_map2object_origin;
@@ -348,7 +348,7 @@ void DummyPerceptionPublisherNode::objectCallback(
348348
}
349349
tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin);
350350
tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin;
351-
dummy_perception_publisher::msg::Object object;
351+
autoware_dummy_perception_publisher::msg::Object object;
352352
object = *msg;
353353
tf2::toMsg(tf_map2object_origin, object.initial_state.pose_covariance.pose);
354354

@@ -369,7 +369,7 @@ void DummyPerceptionPublisherNode::objectCallback(
369369
objects_.push_back(object);
370370
break;
371371
}
372-
case dummy_perception_publisher::msg::Object::DELETE: {
372+
case autoware_dummy_perception_publisher::msg::Object::DELETE: {
373373
for (size_t i = 0; i < objects_.size(); ++i) {
374374
if (objects_.at(i).id.uuid == msg->id.uuid) {
375375
objects_.erase(objects_.begin() + i);
@@ -378,7 +378,7 @@ void DummyPerceptionPublisherNode::objectCallback(
378378
}
379379
break;
380380
}
381-
case dummy_perception_publisher::msg::Object::MODIFY: {
381+
case autoware_dummy_perception_publisher::msg::Object::MODIFY: {
382382
for (size_t i = 0; i < objects_.size(); ++i) {
383383
if (objects_.at(i).id.uuid == msg->id.uuid) {
384384
tf2::Transform tf_input2map;
@@ -396,7 +396,7 @@ void DummyPerceptionPublisherNode::objectCallback(
396396
}
397397
tf2::fromMsg(msg->initial_state.pose_covariance.pose, tf_input2object_origin);
398398
tf_map2object_origin = tf_input2map.inverse() * tf_input2object_origin;
399-
dummy_perception_publisher::msg::Object object;
399+
autoware_dummy_perception_publisher::msg::Object object;
400400
objects_.at(i) = *msg;
401401
tf2::toMsg(tf_map2object_origin, objects_.at(i).initial_state.pose_covariance.pose);
402402
if (use_base_link_z_) {
@@ -418,7 +418,7 @@ void DummyPerceptionPublisherNode::objectCallback(
418418
}
419419
break;
420420
}
421-
case dummy_perception_publisher::msg::Object::DELETEALL: {
421+
case autoware_dummy_perception_publisher::msg::Object::DELETEALL: {
422422
objects_.clear();
423423
break;
424424
}

0 commit comments

Comments
 (0)