Skip to content

Commit

Permalink
Add thread dependency to examples (Rolling) (#237)
Browse files Browse the repository at this point in the history
* Regression test

* Add fix

* Add thread find_package

* updated CMakeLists.txt according to reviewer comments.

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* typo

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* correcting order of C/C++ header includes

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* uncrustify

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* cpplint: changed order of includes in test_action_*.cpp

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* cpplint: changed order of includes test_parameter.cpp

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* cpplint rclc changes

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* resolving cpplint errors

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* resolving cpplint errors

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

* resolving uncrustify and cpplint errors

Signed-off-by: Jan Staschulat (CR/ADA1.2) <[email protected]>

Co-authored-by: Jan Staschulat (CR/ADA1.2) <[email protected]>
  • Loading branch information
Acuadros95 and JanStaschulat authored Jan 25, 2022
1 parent 5ea1a2a commit 0a49ce1
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 20 deletions.
25 changes: 12 additions & 13 deletions rclc/test/rclc/test_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,25 +15,24 @@

#include <gtest/gtest.h>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>

extern "C"
{
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <example_interfaces/action/fibonacci.h>
}

#include <example_interfaces/action/fibonacci.hpp>

#include <chrono>
#include <thread>
#include <memory>
#include <map>
#include <vector>
#include <utility>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <example_interfaces/action/fibonacci.hpp>

#define RCLC_MAX_GOALS 10

using namespace std::chrono_literals;
Expand Down Expand Up @@ -429,12 +428,12 @@ TEST_F(ActionClientTest, goal_accept_feedback_and_result) {
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto & sequence = feedback->sequence;

while (sequence.size() < (size_t) goal->order) {
while (sequence.size() < static_cast<size_t>(goal->order)) {
sequence.push_back(sequence.size());
}

size_t sent_feedback = 0;
while (sent_feedback < (size_t)goal->order) {
while (sent_feedback < static_cast<size_t>(goal->order)) {
goal_handle->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
++sent_feedback;
Expand Down Expand Up @@ -514,12 +513,12 @@ TEST_F(ActionClientTest, goal_accept_feedback_and_abort) {
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto & sequence = feedback->sequence;

while (sequence.size() < (size_t) goal->order) {
while (sequence.size() < static_cast<size_t>(goal->order)) {
sequence.push_back(sequence.size());
}

size_t sent_feedback = 0;
while (sent_feedback < (size_t)goal->order) {
while (sent_feedback < static_cast<size_t>(goal->order)) {
goal_handle->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
++sent_feedback;
Expand Down Expand Up @@ -600,7 +599,7 @@ TEST_F(ActionClientTest, goal_accept_cancel_success) {
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto & sequence = feedback->sequence;

while (sequence.size() < (size_t) goal->order) {
while (sequence.size() < static_cast<size_t>(goal->order)) {
sequence.push_back(sequence.size());
}

Expand Down Expand Up @@ -683,12 +682,12 @@ TEST_F(ActionClientTest, goal_accept_cancel_reject) {
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto & sequence = feedback->sequence;

while (sequence.size() < (size_t) goal->order) {
while (sequence.size() < static_cast<size_t>(goal->order)) {
sequence.push_back(sequence.size());
}

size_t sent_feedback = 0;
while (sent_feedback < (size_t)goal->order) {
while (sent_feedback < static_cast<size_t>(goal->order)) {
goal_handle->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
++sent_feedback;
Expand Down Expand Up @@ -805,7 +804,7 @@ TEST_F(ActionClientTest, multi_goal_accept_feedback_and_result) {
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto & sequence = feedback->sequence;

while (sequence.size() < (size_t) goal->order) {
while (sequence.size() < static_cast<size_t>(goal->order)) {
sequence.push_back(sequence.size());
}

Expand Down
8 changes: 4 additions & 4 deletions rclc/test/rclc/test_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,24 +16,24 @@

#include <gtest/gtest.h>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>

extern "C"
{
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <example_interfaces/action/fibonacci.h>
}

#include <example_interfaces/action/fibonacci.hpp>
#include <chrono>
#include <thread>
#include <memory>
#include <map>
#include <vector>
#include <utility>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <example_interfaces/action/fibonacci.hpp>

#define RCLC_MAX_GOALS 10

using namespace std::chrono_literals;
Expand Down
2 changes: 2 additions & 0 deletions rclc_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ find_package(std_msgs REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclc_parameter REQUIRED)
find_package(Threads REQUIRED)

include_directories(include)

Expand Down Expand Up @@ -57,6 +58,7 @@ add_executable(example_pingpong src/example_pingpong.cpp)
ament_target_dependencies(example_pingpong rcl rclc std_msgs)

add_executable(example_action_server src/example_action_server.c)
target_link_libraries(example_action_server Threads::Threads)
ament_target_dependencies(example_action_server rcl rcl_action rclc example_interfaces)

add_executable(example_action_client src/example_action_client.c)
Expand Down
1 change: 0 additions & 1 deletion rclc_examples/src/example_action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@

#include <stdio.h>
#include <unistd.h>
#include <pthread.h>

#include <rcl/rcl.h>
#include <rcl/error_handling.h>
Expand Down
4 changes: 2 additions & 2 deletions rclc_parameter/test/rclc_parameter/test_parameter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@

#include <gtest/gtest.h>

#include <rclcpp/rclcpp.hpp>

extern "C"
{
#include <rclc/node.h>
Expand All @@ -26,6 +24,8 @@ extern "C"
#include <memory>
#include <vector>

#include <rclcpp/rclcpp.hpp>

using namespace std::chrono_literals;

// #include "parameter_client.hpp"
Expand Down

0 comments on commit 0a49ce1

Please sign in to comment.