Skip to content

Commit

Permalink
add C++ version of default action qos
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <[email protected]>
  • Loading branch information
wjwwood committed May 7, 2019
1 parent 84f46ad commit 136d5a5
Show file tree
Hide file tree
Showing 5 changed files with 75 additions and 8 deletions.
1 change: 1 addition & 0 deletions rclcpp_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ include_directories(include)

set(${PROJECT_NAME}_SRCS
src/client.cpp
src/qos.cpp
src/server.cpp
src/server_goal_handle.cpp
src/types.cpp
Expand Down
31 changes: 31 additions & 0 deletions rclcpp_action/include/rclcpp_action/qos.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP_ACTION__QOS_HPP_
#define RCLCPP_ACTION__QOS_HPP_

#include <rclcpp/qos.hpp>

namespace rclcpp_action
{

class DefaultActionStatusQoS : public rclcpp::QoS
{
public:
DefaultActionStatusQoS();
};

} // namespace rclcpp_action

#endif // RCLCPP_ACTION__QOS_HPP_
28 changes: 28 additions & 0 deletions rclcpp_action/src/qos.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <rclcpp_action/qos.hpp>

#include <rcl_action/default_qos.h>

namespace rclcpp_action
{

DefaultActionStatusQoS::DefaultActionStatusQoS()
: rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rcl_action_qos_profile_status_default))
{
this->get_rmw_qos_profile() = rcl_action_qos_profile_status_default;
}

} // namespace rclcpp_action
6 changes: 4 additions & 2 deletions rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#include "rclcpp_action/exceptions.hpp"
#include "rclcpp_action/create_client.hpp"
#include "rclcpp_action/client.hpp"
#include "rclcpp_action/qos.hpp"
#include "rclcpp_action/types.hpp"

using namespace std::chrono_literals;
Expand Down Expand Up @@ -196,7 +197,8 @@ class TestClient : public ::testing::Test
ret = rcl_action_get_feedback_topic_name(
action_name, allocator, &feedback_topic_name);
ASSERT_EQ(RCL_RET_OK, ret);
feedback_publisher = server_node->create_publisher<ActionFeedbackMessage>(feedback_topic_name);
feedback_publisher =
server_node->create_publisher<ActionFeedbackMessage>(feedback_topic_name, 10);
ASSERT_TRUE(feedback_publisher != nullptr);
allocator.deallocate(feedback_topic_name, allocator.state);

Expand All @@ -205,7 +207,7 @@ class TestClient : public ::testing::Test
action_name, allocator, &status_topic_name);
ASSERT_EQ(RCL_RET_OK, ret);
status_publisher = server_node->create_publisher<ActionStatusMessage>(
status_topic_name, rcl_action_qos_profile_status_default);
status_topic_name, rclcpp_action::DefaultActionStatusQoS());
ASSERT_TRUE(status_publisher != nullptr);
allocator.deallocate(status_topic_name, allocator.state);
server_executor.add_node(server_node);
Expand Down
17 changes: 11 additions & 6 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -367,7 +367,8 @@ TEST_F(TestServer, publish_status_accepted)
// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -428,7 +429,8 @@ TEST_F(TestServer, publish_status_canceling)
// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -483,7 +485,8 @@ TEST_F(TestServer, publish_status_canceled)
// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -540,7 +543,8 @@ TEST_F(TestServer, publish_status_succeeded)
// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -595,7 +599,8 @@ TEST_F(TestServer, publish_status_aborted)
// Subscribe to status messages
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
"fibonacci/_action/status", 10,
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
{
received_msgs.push_back(list);
});
Expand Down Expand Up @@ -651,7 +656,7 @@ TEST_F(TestServer, publish_feedback)
using FeedbackT = Fibonacci::Impl::FeedbackMessage;
std::vector<FeedbackT::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<FeedbackT>(
"fibonacci/_action/feedback", [&received_msgs](FeedbackT::SharedPtr msg)
"fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::SharedPtr msg)
{
received_msgs.push_back(msg);
});
Expand Down

0 comments on commit 136d5a5

Please sign in to comment.