Skip to content

Commit

Permalink
Compile fix for upcomming changes to rclcpp::Executor (#668)
Browse files Browse the repository at this point in the history
Signed-off-by: Janosch Machowinski <[email protected]>
  • Loading branch information
jmachowinski authored Apr 10, 2024
1 parent 62322b8 commit fd033ed
Show file tree
Hide file tree
Showing 10 changed files with 566 additions and 587 deletions.
917 changes: 416 additions & 501 deletions test_tf2/test/buffer_core_test.cpp

Large diffs are not rendered by default.

28 changes: 12 additions & 16 deletions test_tf2/test/permuter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class PermuteOptionBase
public:
virtual void reset() = 0;
virtual bool step() = 0;
virtual ~PermuteOptionBase() {};
virtual ~PermuteOptionBase() {}
};


Expand All @@ -57,14 +57,14 @@ template<class T>
class PermuteOption : public PermuteOptionBase
{
public:
PermuteOption(const std::vector<T>& options, T* output)
PermuteOption(const std::vector<T> & options, T * output)
{
options_ = options;
output_ = output;
reset();
}

virtual ~PermuteOption(){};
virtual ~PermuteOption() {}

void reset()
{
Expand All @@ -77,8 +77,9 @@ class PermuteOption : public PermuteOptionBase
{
std::lock_guard<std::mutex> lock(access_mutex_);
current_element_++;
if (current_element_ == options_.end())
if (current_element_ == options_.end()) {
return false;
}
*output_ = *current_element_;
return true;
}
Expand All @@ -87,7 +88,7 @@ class PermuteOption : public PermuteOptionBase
/// Local storage of the possible values
std::vector<T> options_;
/// The output variable
T* output_;
T * output_;
typedef typename std::vector<T>::iterator V_T_iterator;
/// The last updated element
V_T_iterator current_element_;
Expand All @@ -104,15 +105,15 @@ class Permuter
{
public:
/** \brief Destructor to clean up allocated data */
virtual ~Permuter(){ clearAll();};
virtual ~Permuter() {clearAll();}


/** \brief Add a set of values and an output to the iteration
* @param values The set of possible values for this output
* @param output The value to set at each iteration
*/
template<class T>
void addOptionSet(const std::vector<T>& values, T* output)
void addOptionSet(const std::vector<T> & values, T * output)
{
std::lock_guard<std::mutex> lock(access_mutex_);
options_.emplace_back(std::make_unique<PermuteOption<T>>(values, output));
Expand All @@ -123,8 +124,7 @@ class Permuter
/** \brief Reset the internal counters */
void reset()
{
for (unsigned int level= 0; level < options_.size(); level++)
{
for (unsigned int level = 0; level < options_.size(); level++) {
options_[level]->reset();
}
}
Expand All @@ -136,15 +136,11 @@ class Permuter
{
std::lock_guard<std::mutex> lock(access_mutex_);
// base case just iterating
for (size_t level = 0; level < options_.size(); level++)
{
if(options_[level]->step())
{
for (size_t level = 0; level < options_.size(); level++) {
if (options_[level]->step()) {
//printf("stepping level %d returning true \n", level);
return true;
}
else
{
} else {
//printf("reseting level %d\n", level);
options_[level]->reset();
}
Expand Down
41 changes: 23 additions & 18 deletions test_tf2/test/test_buffer_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,21 @@ static const double EPS = 1e-3;
TEST(tf2_ros, buffer_client)
{
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("tf_action_node");
std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(node, "tf_action");
std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(
node,
"tf_action");

rclcpp::executors::SingleThreadedExecutor executor;

executor.add_node(node);

std::cout << "FOOO" << std::endl;

// Start spinning in a thread
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));
[&executor]() {
executor.spin();
});

//make sure that things are set up
ASSERT_TRUE(client->waitForServer(std::chrono::seconds(4)));
Expand All @@ -72,19 +78,17 @@ TEST(tf2_ros, buffer_client)
p1.point.y = 0.0;
p1.point.z = 0.0;

try
{
try {
geometry_msgs::msg::PointStamped p2 = client->transform(p1, "b");
RCLCPP_INFO(node->get_logger(),
"p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)", p1.point.x,
p1.point.y, p1.point.z, p2.point.x, p2.point.y, p2.point.z);
RCLCPP_INFO(
node->get_logger(),
"p1: (%.2f, %.2f, %.2f), p2: (%.2f, %.2f, %.2f)", p1.point.x,
p1.point.y, p1.point.z, p2.point.x, p2.point.y, p2.point.z);

EXPECT_NEAR(p2.point.x, -5.0, EPS);
EXPECT_NEAR(p2.point.y, -6.0, EPS);
EXPECT_NEAR(p2.point.z, -7.0, EPS);
}
catch(tf2::TransformException& ex)
{
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(node->get_logger(), "Failed to transform: %s", ex.what());
ASSERT_FALSE("Should not get here");
}
Expand All @@ -96,23 +100,26 @@ TEST(tf2_ros, buffer_client)
TEST(tf2_ros, buffer_client_different_types)
{
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("tf_action_node");
std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(node, "tf_action");
std::unique_ptr<tf2_ros::BufferClient> client = std::make_unique<tf2_ros::BufferClient>(
node,
"tf_action");

rclcpp::executors::SingleThreadedExecutor executor;

executor.add_node(node);

// Start spinning in a thread
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));
[&executor]() {
executor.spin();
});

//make sure that things are set up
ASSERT_TRUE(client->waitForServer(std::chrono::seconds(4)));

tf2::Stamped<KDL::Vector> k1(KDL::Vector(0, 0, 0), tf2::TimePoint(), "a");

try
{
try {
tf2::Stamped<btVector3> b1;
client->transform(k1, b1, "b");
RCLCPP_ERROR(node->get_logger(), "Bullet: (%.4f, %.4f, %.4f)", b1[0], b1[1], b1[2]);
Expand All @@ -122,9 +129,7 @@ TEST(tf2_ros, buffer_client_different_types)
EXPECT_NEAR(b1[2], -7.0, EPS);
EXPECT_EQ(b1.frame_id_, "b");
EXPECT_EQ(k1.frame_id_, "a");
}
catch(tf2::TransformException& ex)
{
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(node->get_logger(), "Failed to transform: %s", ex.what());
ASSERT_FALSE("Should not get here");
}
Expand All @@ -134,7 +139,7 @@ TEST(tf2_ros, buffer_client_different_types)

}

int main(int argc, char** argv)
int main(int argc, char ** argv)
{
// This is needed because we need to wait a little bit for the other nodes
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
Expand Down
7 changes: 5 additions & 2 deletions test_tf2/test/test_buffer_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <rclcpp/rclcpp.hpp>
#include <memory>

int main(int argc, char** argv)
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

Expand All @@ -49,7 +49,10 @@ int main(int argc, char** argv)
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
tf2_ros::TransformListener tfl(buffer, node, false);
std::unique_ptr<tf2_ros::BufferServer> server = std::make_unique<tf2_ros::BufferServer>(buffer, node, "tf_action");
std::unique_ptr<tf2_ros::BufferServer> server = std::make_unique<tf2_ros::BufferServer>(
buffer,
node,
"tf_action");

rclcpp::spin(node);
}
Loading

0 comments on commit fd033ed

Please sign in to comment.