Skip to content

Commit

Permalink
Review feedback
Browse files Browse the repository at this point in the history
* Delete CHANGELOG.rst
* Enable cppcheck
* Remove all references to rosbag2/ros2bag

Signed-off-by: Nikolai Morin <[email protected]>
  • Loading branch information
nnmm committed Dec 17, 2020
1 parent d417484 commit 520a919
Show file tree
Hide file tree
Showing 7 changed files with 17 additions and 25 deletions.
8 changes: 0 additions & 8 deletions rclcpp_generic/CHANGELOG.rst

This file was deleted.

2 changes: 0 additions & 2 deletions rclcpp_generic/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -82,8 +82,6 @@ if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(test_msgs REQUIRED)
# explicitly disable cppcheck
set(ament_cmake_cppcheck_FOUND TRUE)
ament_lint_auto_find_test_dependencies()

# This test is independent from the rmw implementation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ namespace rclcpp_generic
class GenericPublisher : public rclcpp::PublisherBase
{
public:
// cppcheck-suppress unknownMacro
RCLCPP_SMART_PTR_DEFINITIONS(GenericPublisher)

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ namespace rclcpp_generic
class GenericSubscription : public rclcpp::SubscriptionBase
{
public:
// cppcheck-suppress unknownMacro
RCLCPP_SMART_PTR_DEFINITIONS(GenericSubscription)

/**
Expand Down
10 changes: 5 additions & 5 deletions rclcpp_generic/src/rclcpp_generic/generic_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,19 @@

#include "rclcpp_generic/typesupport_helpers.hpp"

namespace rclcpp_generic
{

namespace
{
rcl_publisher_options_t rosbag2_get_publisher_options(const rclcpp::QoS & qos)
rcl_publisher_options_t get_publisher_options(const rclcpp::QoS & qos)
{
auto options = rcl_publisher_get_default_options();
options.qos = qos.get_rmw_qos_profile();
return options;
}
} // unnamed namespace

namespace rclcpp_generic
{

std::shared_ptr<GenericPublisher> GenericPublisher::create(
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
const std::string & topic_name, const std::string & topic_type, const rclcpp::QoS & qos,
Expand All @@ -54,7 +54,7 @@ GenericPublisher::GenericPublisher(
const std::string & topic_type,
const rclcpp::QoS & qos)
: rclcpp::PublisherBase(node_base, topic_name, *rclcpp_generic::get_typesupport_handle(
topic_type, "rosidl_typesupport_cpp", ts_lib), rosbag2_get_publisher_options(qos)), ts_lib_(
topic_type, "rosidl_typesupport_cpp", ts_lib), get_publisher_options(qos)), ts_lib_(
ts_lib)
{}

Expand Down
10 changes: 5 additions & 5 deletions rclcpp_generic/src/rclcpp_generic/generic_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,19 @@
#include "rcl/subscription.h"
#include "rclcpp_generic/typesupport_helpers.hpp"

namespace rclcpp_generic
{

namespace
{
rcl_subscription_options_t rosbag2_get_subscription_options(const rclcpp::QoS & qos)
rcl_subscription_options_t get_subscription_options(const rclcpp::QoS & qos)
{
auto options = rcl_subscription_get_default_options();
options.qos = qos.get_rmw_qos_profile();
return options;
}
} // unnamed namespace

namespace rclcpp_generic
{

std::shared_ptr<GenericSubscription> GenericSubscription::create(
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
const std::string & topic_name,
Expand Down Expand Up @@ -71,7 +71,7 @@ GenericSubscription::GenericSubscription(
*rclcpp_generic::get_typesupport_handle(
topic_type, "rosidl_typesupport_cpp", ts_lib),
topic_name,
rosbag2_get_subscription_options(qos),
get_subscription_options(qos),
true),
callback_(callback)
{}
Expand Down
10 changes: 5 additions & 5 deletions rclcpp_generic/test/rclcpp_generic/test_pubsub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@
using namespace ::testing; // NOLINT
using namespace rclcpp_generic; // NOLINT

class RosBag2NodeFixture : public Test
class RclcppGenericNodeFixture : public Test
{
public:
RosBag2NodeFixture()
RclcppGenericNodeFixture()
{
node_ = std::make_shared<rclcpp::Node>("pubsub");
publisher_node_ = std::make_shared<rclcpp::Node>(
Expand Down Expand Up @@ -116,7 +116,7 @@ class RosBag2NodeFixture : public Test
};


TEST_F(RosBag2NodeFixture, publisher_and_subscriber_work)
TEST_F(RclcppGenericNodeFixture, publisher_and_subscriber_work)
{
// We currently publish more messages because they can get lost
std::vector<std::string> test_messages = {"Hello World", "Hello World"};
Expand Down Expand Up @@ -145,7 +145,7 @@ TEST_F(RosBag2NodeFixture, publisher_and_subscriber_work)
EXPECT_THAT(subscribed_messages[0], StrEq("Hello World"));
}

TEST_F(RosBag2NodeFixture, generic_subscription_uses_qos)
TEST_F(RclcppGenericNodeFixture, generic_subscription_uses_qos)
{
// If the GenericSubscription does not use the provided QoS profile,
// its request will be incompatible with the Publisher's offer and no messages will be passed.
Expand All @@ -166,7 +166,7 @@ TEST_F(RosBag2NodeFixture, generic_subscription_uses_qos)
ASSERT_TRUE(wait_for(connected, 5s));
}

TEST_F(RosBag2NodeFixture, generic_publisher_uses_qos)
TEST_F(RclcppGenericNodeFixture, generic_publisher_uses_qos)
{
// If the GenericPublisher does not use the provided QoS profile,
// its offer will be incompatible with the Subscription's request and no messages will be passed.
Expand Down

0 comments on commit 520a919

Please sign in to comment.