Skip to content

Commit

Permalink
Corrected publish calls with shared_ptr signature
Browse files Browse the repository at this point in the history
Signed-off-by: ivanpauno <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno authored and wjwwood committed May 5, 2019
1 parent c548e3b commit efd6cfb
Show file tree
Hide file tree
Showing 12 changed files with 30 additions and 30 deletions.
2 changes: 1 addition & 1 deletion test_communication/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ void publish(
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(messages[message_index]);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
Expand Down
2 changes: 1 addition & 1 deletion test_communication/test/test_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ void publish(
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(messages[message_index]);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ TEST_F(CLASSNAME(TestMessageSerialization, RMW_IMPLEMENTATION), serialized_callb
rclcpp::Rate loop_rate(10);
for (auto i = 0u; i < 10; ++i) {
msg->uint8_value = i;
publisher->publish(msg);
publisher->publish(*msg);
rclcpp::spin_some(node);
loop_rate.sleep();
}
Expand Down
2 changes: 1 addition & 1 deletion test_communication/test/test_subscription_valid_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ int main(int argc, char ** argv)
printf("publishing message #%u\n", index);
auto msg = std::make_shared<test_communication::msg::UInt32>();
msg->data = index;
publisher->publish(msg);
publisher->publish(*msg);
++index;
message_rate.sleep();
rclcpp::spin_some(node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ TEST(
rclcpp::Publisher<test_rclcpp::msg::UInt32>::SharedPtr publisher,
test_rclcpp::msg::UInt32::SharedPtr msg)
{
publisher->publish(msg);
publisher->publish(*msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down
12 changes: 6 additions & 6 deletions test_rclcpp/test/test_intra_process.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_
std::this_thread::sleep_for(std::chrono::milliseconds(1));

msg->data = 1;
publisher->publish(msg);
publisher->publish(*msg);
ASSERT_EQ(0, counter);

// wait for the first callback
Expand All @@ -108,13 +108,13 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_
ASSERT_EQ(1, counter);

msg->data = 2;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 3;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 4;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 5;
publisher->publish(msg);
publisher->publish(*msg);
ASSERT_EQ(1, counter);

// while four messages have been published one callback should be triggered here
Expand Down Expand Up @@ -158,7 +158,7 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_
// the subscriber goes out of scope and should be not receive any callbacks anymore

msg->data = 6;
publisher->publish(msg);
publisher->publish(*msg);

std::this_thread::sleep_for(std::chrono::milliseconds(25));

Expand Down
6 changes: 3 additions & 3 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
EXPECT_EQ(0, counter.load());

++msg->data;
pub->publish(msg);
pub->publish(*msg);

// test spin_some
// Expectation: The message was published and all subscriptions fired the callback.
Expand Down Expand Up @@ -131,7 +131,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
executor.cancel();
return;
}
pub->publish(msg);
pub->publish(*msg);
};
auto timer = node->create_wall_timer(std::chrono::milliseconds(1), publish_callback);

Expand Down Expand Up @@ -316,7 +316,7 @@ static inline void multi_access_publisher(bool intra_process)
}
msg->data = ++timer_counter;
printf("Publishing message %u\n", timer_counter.load());
pub->publish(msg);
pub->publish(*msg);
};
std::vector<rclcpp::TimerBase::SharedPtr> timers;
// timers will fire simultaneously in each thread
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ TEST(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference
rclcpp::Publisher<test_rclcpp::msg::UInt32>::SharedPtr publisher,
test_rclcpp::msg::UInt32::SharedPtr msg)
{
publisher->publish(msg);
publisher->publish(*msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_repeated_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ TEST(CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), subscrip
executor.spin_node_some(node);

msg->data = 1;
publisher->publish(msg);
publisher->publish(*msg);

std::this_thread::sleep_for(std::chrono::milliseconds(50));
printf("spin_node_some()\n");
Expand All @@ -84,7 +84,7 @@ TEST(CLASSNAME(test_repeated_publisher_subscriber, RMW_IMPLEMENTATION), subscrip
executor.spin_node_some(node);

msg->data = 2;
publisher->publish(msg);
publisher->publish(*msg);

std::this_thread::sleep_for(std::chrono::milliseconds(50));
printf("spin_node_some()\n");
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) {
{
executor.cancel();
// Try to publish after canceling. The callback should never trigger.
pub->publish(msg);
pub->publish(*msg);
};
auto timer = node->create_wall_timer(std::chrono::milliseconds(5), cancel_callback);
executor.add_node(node);
Expand Down
22 changes: 11 additions & 11 deletions test_rclcpp/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning
ASSERT_EQ(0, counter);

msg->data = 1;
publisher->publish(msg);
publisher->publish(*msg);
ASSERT_EQ(0, counter);

// spin until the subscription is called or a timeout occurs
Expand All @@ -121,13 +121,13 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning
ASSERT_EQ(1, counter);

msg->data = 2;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 3;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 4;
publisher->publish(msg);
publisher->publish(*msg);
msg->data = 5;
publisher->publish(msg);
publisher->publish(*msg);
ASSERT_EQ(1, counter);

// while four messages have been published one callback should be triggered here
Expand Down Expand Up @@ -161,7 +161,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning
// the subscriber goes out of scope and should be not receive any callbacks anymore

msg->data = 6;
publisher->publish(msg);
publisher->publish(*msg);

// check that no further callbacks have been invoked
printf("spin_until_future_complete(short timeout) - no callbacks expected\n");
Expand Down Expand Up @@ -202,7 +202,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c
{
// Create a ConstSharedPtr message to publish
test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg);
publisher->publish(const_msg);
publisher->publish(*const_msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down Expand Up @@ -250,7 +250,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION),
{
// Create a ConstSharedPtr message to publish
test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg);
publisher->publish(const_msg);
publisher->publish(*const_msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down Expand Up @@ -284,7 +284,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION),
{
// Create a ConstSharedPtr message to publish
test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg);
publisher->publish(const_msg);
publisher->publish(*const_msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down Expand Up @@ -320,7 +320,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c
rclcpp::Publisher<test_rclcpp::msg::UInt32>::SharedPtr publisher,
test_rclcpp::msg::UInt32::SharedPtr msg)
{
publisher->publish(msg);
publisher->publish(*msg);
};
// call the test template
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
Expand Down Expand Up @@ -356,7 +356,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscription)
{
// Create a ConstSharedPtr message to publish
test_rclcpp::msg::UInt32::ConstSharedPtr const_msg(msg);
publisher->publish(const_msg);
publisher->publish(*const_msg);
};
// code for custom "pre subscription" hook
auto pre_subscription_hook =
Expand Down
2 changes: 1 addition & 1 deletion test_security/test/test_secure_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ int8_t attempt_publish(
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(messages[message_index]);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
Expand Down

0 comments on commit efd6cfb

Please sign in to comment.