@@ -37,7 +37,7 @@ using autoware_auto_perception_msgs::msg::TrackedObject;
37
37
using autoware_auto_perception_msgs::msg::TrackedObjects;
38
38
39
39
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)
41
41
: length(object.shape.dimensions.x),
42
42
width(object.shape.dimensions.y),
43
43
height(object.shape.dimensions.z),
@@ -108,7 +108,7 @@ ObjectInfo::ObjectInfo(
108
108
}
109
109
110
110
TrackedObject ObjectInfo::toTrackedObject (
111
- const dummy_perception_publisher ::msg::Object & object) const
111
+ const autoware_dummy_perception_publisher ::msg::Object & object) const
112
112
{
113
113
TrackedObject tracked_object;
114
114
tracked_object.kinematics .pose_with_covariance = pose_covariance_;
@@ -162,7 +162,7 @@ DummyPerceptionPublisherNode::DummyPerceptionPublisherNode()
162
162
this ->create_publisher <tier4_perception_msgs::msg::DetectedObjectsWithFeature>(
163
163
" output/dynamic_object" , qos);
164
164
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>(
166
166
" input/object" , 100 ,
167
167
std::bind (&DummyPerceptionPublisherNode::objectCallback, this , std::placeholders::_1));
168
168
@@ -329,10 +329,10 @@ void DummyPerceptionPublisherNode::timerCallback()
329
329
}
330
330
331
331
void DummyPerceptionPublisherNode::objectCallback (
332
- const dummy_perception_publisher ::msg::Object::ConstSharedPtr msg)
332
+ const autoware_dummy_perception_publisher ::msg::Object::ConstSharedPtr msg)
333
333
{
334
334
switch (msg->action ) {
335
- case dummy_perception_publisher ::msg::Object::ADD: {
335
+ case autoware_dummy_perception_publisher ::msg::Object::ADD: {
336
336
tf2::Transform tf_input2map;
337
337
tf2::Transform tf_input2object_origin;
338
338
tf2::Transform tf_map2object_origin;
@@ -348,7 +348,7 @@ void DummyPerceptionPublisherNode::objectCallback(
348
348
}
349
349
tf2::fromMsg (msg->initial_state .pose_covariance .pose , tf_input2object_origin);
350
350
tf_map2object_origin = tf_input2map.inverse () * tf_input2object_origin;
351
- dummy_perception_publisher ::msg::Object object;
351
+ autoware_dummy_perception_publisher ::msg::Object object;
352
352
object = *msg;
353
353
tf2::toMsg (tf_map2object_origin, object.initial_state .pose_covariance .pose );
354
354
@@ -369,7 +369,7 @@ void DummyPerceptionPublisherNode::objectCallback(
369
369
objects_.push_back (object);
370
370
break ;
371
371
}
372
- case dummy_perception_publisher ::msg::Object::DELETE: {
372
+ case autoware_dummy_perception_publisher ::msg::Object::DELETE: {
373
373
for (size_t i = 0 ; i < objects_.size (); ++i) {
374
374
if (objects_.at (i).id .uuid == msg->id .uuid ) {
375
375
objects_.erase (objects_.begin () + i);
@@ -378,7 +378,7 @@ void DummyPerceptionPublisherNode::objectCallback(
378
378
}
379
379
break ;
380
380
}
381
- case dummy_perception_publisher ::msg::Object::MODIFY: {
381
+ case autoware_dummy_perception_publisher ::msg::Object::MODIFY: {
382
382
for (size_t i = 0 ; i < objects_.size (); ++i) {
383
383
if (objects_.at (i).id .uuid == msg->id .uuid ) {
384
384
tf2::Transform tf_input2map;
@@ -396,7 +396,7 @@ void DummyPerceptionPublisherNode::objectCallback(
396
396
}
397
397
tf2::fromMsg (msg->initial_state .pose_covariance .pose , tf_input2object_origin);
398
398
tf_map2object_origin = tf_input2map.inverse () * tf_input2object_origin;
399
- dummy_perception_publisher ::msg::Object object;
399
+ autoware_dummy_perception_publisher ::msg::Object object;
400
400
objects_.at (i) = *msg;
401
401
tf2::toMsg (tf_map2object_origin, objects_.at (i).initial_state .pose_covariance .pose );
402
402
if (use_base_link_z_) {
@@ -418,7 +418,7 @@ void DummyPerceptionPublisherNode::objectCallback(
418
418
}
419
419
break ;
420
420
}
421
- case dummy_perception_publisher ::msg::Object::DELETEALL: {
421
+ case autoware_dummy_perception_publisher ::msg::Object::DELETEALL: {
422
422
objects_.clear ();
423
423
break ;
424
424
}
0 commit comments