Skip to content

Commit

Permalink
updated unit test for intraprocess manager to match new interface
Browse files Browse the repository at this point in the history
Signed-off-by: Joshua Hampp <j.hampp@denso-adas.de>
  • Loading branch information
Joshua Hampp committed Apr 22, 2020
1 parent fada8a0 commit 87b5df9
Showing 1 changed file with 14 additions and 0 deletions.
14 changes: 14 additions & 0 deletions rclcpp/test/test_intra_process_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#define RCLCPP_BUILDING_LIBRARY 1
#include "rclcpp/allocator/allocator_common.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rclcpp/qos.hpp"
#include "rmw/types.h"
#include "rmw/qos_profiles.h"
Expand Down Expand Up @@ -212,6 +214,18 @@ class SubscriptionIntraProcessBase
return topic_name;
}

bool
is_serialized() const
{
return false;
}

void
provide_serialized_intra_process_message(const rclcpp::SerializedMessage & serialized_message)
{
(void)serialized_message;
}

rmw_qos_profile_t qos_profile;
const char * topic_name;
};
Expand Down

0 comments on commit 87b5df9

Please sign in to comment.