Skip to content

Commit

Permalink
Revert unintended changes
Browse files Browse the repository at this point in the history
  • Loading branch information
nhatao committed Jun 25, 2024
1 parent 1a406d6 commit 3ad68f9
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 41 deletions.
77 changes: 38 additions & 39 deletions neonavigation_common/test/src/test_compat.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@

#include <cstdlib>

#include "rclcpp/rclcpp.hpp"
#include <std_msgs/msg/bool.hpp>
#include <std_srvs/srv/empty.hpp>
#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_srvs/Empty.h>

#include <gtest/gtest.h>

Expand All @@ -54,26 +54,26 @@ TEST(NeonavigationCompat, CompatMode)
neonavigation_common::compat::current_level = 3;
neonavigation_common::compat::default_level = neonavigation_common::compat::supported_level;

rclcpp::Node("/").setParam("neonavigation_compatible", 2);
ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
ASSERT_NO_THROW(
{
neonavigation_common::compat::checkCompatMode();
}); // NOLINT(whitespace/braces)

rclcpp::Node("/").setParam("neonavigation_compatible", 3);
ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
ASSERT_NO_THROW(
{
neonavigation_common::compat::checkCompatMode();
}); // NOLINT(whitespace/braces)

rclcpp::Node("/").setParam("neonavigation_compatible", 4);
ros::NodeHandle("/").setParam("neonavigation_compatible", 4);
ASSERT_THROW(
{
neonavigation_common::compat::checkCompatMode();
}, // NOLINT(whitespace/braces)
std::runtime_error);

rclcpp::Node("/").setParam("neonavigation_compatible", 1);
ros::NodeHandle("/").setParam("neonavigation_compatible", 1);
ASSERT_THROW(
{
neonavigation_common::compat::checkCompatMode();
Expand All @@ -84,22 +84,22 @@ TEST(NeonavigationCompat, CompatMode)
class NeonavigationCompatCallbacks
{
public:
rclcpp::Node nh_;
rclcpp::Node pnh_;
std_msgs::msg::Bool::ConstSharedPtr msg_;
mutable std_msgs::msg::Bool::ConstSharedPtr msg_const_;
ros::NodeHandle nh_;
ros::NodeHandle pnh_;
std_msgs::Bool::ConstPtr msg_;
mutable std_msgs::Bool::ConstPtr msg_const_;
bool srv_called_;

void cb(const std_msgs::msg::Bool::ConstSharedPtr& msg)
void cb(const std_msgs::Bool::ConstPtr& msg)
{
msg_ = msg;
}
void cbConst(const std_msgs::msg::Bool::ConstSharedPtr& msg) const
void cbConst(const std_msgs::Bool::ConstPtr& msg) const
{
msg_const_ = msg;
}

bool cbSrv(std_srvs::srv::Empty::Request& req, std_srvs::srv::Empty::Response& res)
bool cbSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
{
srv_called_ = true;
return true;
Expand All @@ -120,65 +120,65 @@ TEST(NeonavigationCompat, Subscribe)

NeonavigationCompatCallbacks cls;

auto pub_old = cls.pnh_.advertise<std_msgs::msg::Bool>("test_old", 1, true);
auto pub_new = cls.nh_.advertise<std_msgs::msg::Bool>("test_new", 1, true);
std_msgs::msg::Bool msg;
ros::Publisher pub_old = cls.pnh_.advertise<std_msgs::Bool>("test_old", 1, true);
ros::Publisher pub_new = cls.nh_.advertise<std_msgs::Bool>("test_new", 1, true);
std_msgs::Bool msg;
msg.data = false;
pub_old.publish(msg);
msg.data = true;
pub_new.publish(msg);

{
rclcpp::Node("/").setParam("neonavigation_compatible", 2);
ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
ros::Subscriber sub = neonavigation_common::compat::subscribe(
cls.nh_, "test_new",
cls.pnh_, "test_old",
1,
&NeonavigationCompatCallbacks::cb, &cls);
rclcpp::Duration(0.1).sleep();
rclcpp::spin_some(node);
ros::Duration(0.1).sleep();
ros::spinOnce();
ASSERT_TRUE(static_cast<bool>(cls.msg_));
ASSERT_EQ(false, static_cast<bool>(cls.msg_->data));
}

{
rclcpp::Node("/").setParam("neonavigation_compatible", 3);
ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
cls.msg_ = nullptr;
ros::Subscriber sub = neonavigation_common::compat::subscribe(
cls.nh_, "test_new",
cls.pnh_, "test_old",
1,
&NeonavigationCompatCallbacks::cb, &cls);
rclcpp::Duration(0.1).sleep();
rclcpp::spin_some(node);
ros::Duration(0.1).sleep();
ros::spinOnce();
ASSERT_TRUE(static_cast<bool>(cls.msg_));
ASSERT_EQ(true, static_cast<bool>(cls.msg_->data));
}

{
rclcpp::Node("/").setParam("neonavigation_compatible", 2);
ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
cls.msg_ = nullptr;
ros::Subscriber sub = neonavigation_common::compat::subscribe(
cls.nh_, "test_new",
cls.pnh_, "test_old",
1,
&NeonavigationCompatCallbacks::cbConst, &cls);
rclcpp::Duration(0.1).sleep();
rclcpp::spin_some(node);
ros::Duration(0.1).sleep();
ros::spinOnce();
ASSERT_TRUE(static_cast<bool>(cls.msg_const_));
ASSERT_EQ(false, static_cast<bool>(cls.msg_const_->data));
}

{
rclcpp::Node("/").setParam("neonavigation_compatible", 3);
ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
cls.msg_ = nullptr;
ros::Subscriber sub = neonavigation_common::compat::subscribe(
cls.nh_, "test_new",
cls.pnh_, "test_old",
1,
&NeonavigationCompatCallbacks::cbConst, &cls);
rclcpp::Duration(0.1).sleep();
rclcpp::spin_some(node);
ros::Duration(0.1).sleep();
ros::spinOnce();
ASSERT_TRUE(static_cast<bool>(cls.msg_const_));
ASSERT_EQ(true, static_cast<bool>(cls.msg_const_->data));
}
Expand All @@ -191,33 +191,33 @@ TEST(NeonavigationCompat, AdvertiseService)
neonavigation_common::compat::default_level = neonavigation_common::compat::supported_level;

NeonavigationCompatCallbacks cls;
ros::ServiceClient cli_new = cls.nh_.serviceClient<std_srvs::srv::Empty>("srv_new");
ros::ServiceClient cli_old = cls.pnh_.serviceClient<std_srvs::srv::Empty>("srv_old");
ros::ServiceClient cli_new = cls.nh_.serviceClient<std_srvs::Empty>("srv_new");
ros::ServiceClient cli_old = cls.pnh_.serviceClient<std_srvs::Empty>("srv_old");

ros::AsyncSpinner spinner(1);
spinner.start();

{
rclcpp::Node("/").setParam("neonavigation_compatible", 2);
ros::NodeHandle("/").setParam("neonavigation_compatible", 2);

ros::ServiceServer srv = neonavigation_common::compat::advertiseService(
cls.nh_, "srv_new",
cls.pnh_, "srv_old",
&NeonavigationCompatCallbacks::cbSrv, &cls);
rclcpp::Duration(0.1).sleep();
std_srvs::srv::Empty empty;
ros::Duration(0.1).sleep();
std_srvs::Empty empty;
ASSERT_TRUE(cli_old.call(empty.request, empty.response));
}

{
rclcpp::Node("/").setParam("neonavigation_compatible", 3);
ros::NodeHandle("/").setParam("neonavigation_compatible", 3);

ros::ServiceServer srv = neonavigation_common::compat::advertiseService(
cls.nh_, "srv_new",
cls.pnh_, "srv_old",
&NeonavigationCompatCallbacks::cbSrv, &cls);
rclcpp::Duration(0.1).sleep();
std_srvs::srv::Empty empty;
ros::Duration(0.1).sleep();
std_srvs::Empty empty;
ASSERT_TRUE(cli_new.call(empty.request, empty.response));
}

Expand All @@ -227,8 +227,7 @@ TEST(NeonavigationCompat, AdvertiseService)
int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("test_compat");
ros::init(argc, argv, "test_compat");

return RUN_ALL_TESTS();
}
4 changes: 2 additions & 2 deletions safety_limiter/test/test/safety_limiter_rostest.test
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@
<rosparam param="footprint">[[0.0, -0.1], [0.0, 0.1], [-2.0, 0.1], [-2.0, -0.1]]</rosparam>
<param name="allow_empty_cloud" value="false" />
<param name="watchdog_interval" value="0.2" />
<param name="max_linear_vel" value="15"/>
<param name="max_angular_vel" value="25"/>
<param name="max_linear_vel" value="1.5"/>
<param name="max_angular_vel" value="2.5"/>
<param name="cloud_timeout" value="0.2" />
<param name="freq" value="15.0" />
<param name="dt" value="0.01" />
Expand Down

0 comments on commit 3ad68f9

Please sign in to comment.