Skip to content

Commit

Permalink
make linters happy
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 22, 2024
1 parent cc58914 commit b90741c
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 18 deletions.
6 changes: 4 additions & 2 deletions image_proc/test/rostest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,12 @@
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include <gtest/gtest.h>

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <gtest/gtest.h>
#include <cv_bridge/cv_bridge.hpp>

#include <camera_calibration_parsers/parse.hpp>
Expand Down Expand Up @@ -107,6 +108,7 @@ class ImageProcTest
{
cam_pub.publish(*raw_image, cam_info);
}

public:
bool has_new_image_{false};
void callback(const sensor_msgs::msg::Image::ConstSharedPtr & /*msg*/)
Expand All @@ -125,7 +127,7 @@ TEST_F(ImageProcTest, monoSubscription)
RCLCPP_INFO(node->get_logger(), "Publishing");

RCLCPP_INFO(node->get_logger(), "Spinning");
while(!has_new_image_) {
while (!has_new_image_) {
publishRaw();
rclcpp::spin_some(node);
}
Expand Down
10 changes: 0 additions & 10 deletions image_proc/test/test_bayer.xml

This file was deleted.

16 changes: 10 additions & 6 deletions image_proc/test/test_rectify.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,14 @@
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include <gtest/gtest.h>

#include <algorithm>
#include <chrono>
#include <string>
#include <thread>

#include <rclcpp/rclcpp.hpp>
#include <gtest/gtest.h>
#include <cv_bridge/cv_bridge.hpp>

#include <camera_calibration_parsers/parse.hpp>
Expand Down Expand Up @@ -132,14 +133,16 @@ class ImageProcRectifyTest
std_msgs::msg::Header(), "bgr8", distorted_image_).toImageMsg();

rclcpp::NodeOptions options;
options.arguments({
options.arguments(
{
"--ros-args", "-r", std::string("__ns:=") + "/camera",
"-r", "/camera/image:=/camera/image_raw"});
node_rectify = std::make_shared<image_proc::RectifyNode>(options);

spin_rectify_thread = std::thread([this](){
rclcpp::spin(node_rectify);
});
spin_rectify_thread = std::thread(
[this]() {
rclcpp::spin(node_rectify);
});

// Create raw camera subscriber and publisher
image_transport::ImageTransport it(node);
Expand Down Expand Up @@ -193,7 +196,8 @@ TEST_F(ImageProcRectifyTest, rectifyTest)
RCLCPP_INFO(node->get_logger(), "In test. Subscribing.");
image_transport::ImageTransport it(node);
cam_sub_ = it.subscribe(
topic_rect_, 1, &ImageProcRectifyTest::imageCallback,
topic_rect_, rclcpp::SensorDataQoS().get_rmw_qos_profile(),
&ImageProcRectifyTest::imageCallback,
dynamic_cast<ImageProcRectifyTest *>(this));

// Wait for image_proc to be operational
Expand Down

0 comments on commit b90741c

Please sign in to comment.