11
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
- #include < gtest/gtest.h>
15
14
#include " service_log_checker.hpp"
15
+
16
16
#include < rclcpp/node_options.hpp>
17
+
18
+ #include < gtest/gtest.h>
19
+
17
20
#include < memory>
18
21
#include < string>
19
22
@@ -23,38 +26,38 @@ using ServiceLogChecker = autoware::component_interface_tools::ServiceLogChecker
23
26
24
27
TEST (ServiceCheckerTest, ServiceChecker)
25
28
{
26
- class PubManager : public rclcpp ::Node
29
+ class PubManager : public rclcpp ::Node
30
+ {
31
+ public:
32
+ PubManager () : Node(" test_pub_node" )
27
33
{
28
- public:
29
- PubManager () : Node(" test_pub_node" )
30
- {
31
- pub_odom_ = create_publisher<ServiceLog>(" service_log" , 1 );
32
- sub_odom_ = create_subscription<DiagnosticArray>(
33
- " /diagnostics" , 1 , std::bind (&PubManager::on_service_log, this , std::placeholders::_1));
34
- }
35
- rclcpp::Publisher<ServiceLog>::SharedPtr pub_odom_;
36
- rclcpp::Subscription<DiagnosticArray>::SharedPtr sub_odom_;
37
- bool flag = false ;
38
- void on_service_log (const DiagnosticArray::ConstSharedPtr msg)
39
- {
40
- if (msg->status .size () > 0 ) {
41
- auto diag_array = msg->status [0 ].message .c_str ();
42
- EXPECT_EQ (diag_array, " ERROR" );
43
- flag = true ;
44
- }
34
+ pub_odom_ = create_publisher<ServiceLog>(" service_log" , 1 );
35
+ sub_odom_ = create_subscription<DiagnosticArray>(
36
+ " /diagnostics" , 1 , std::bind (&PubManager::on_service_log, this , std::placeholders::_1));
37
+ }
38
+ rclcpp::Publisher<ServiceLog>::SharedPtr pub_odom_;
39
+ rclcpp::Subscription<DiagnosticArray>::SharedPtr sub_odom_;
40
+ bool flag = false ;
41
+ void on_service_log (const DiagnosticArray::ConstSharedPtr msg)
42
+ {
43
+ if (msg->status .size () > 0 ) {
44
+ auto diag_array = msg->status [0 ].message .c_str ();
45
+ EXPECT_EQ (diag_array, " ERROR" );
46
+ flag = true ;
45
47
}
46
- };
47
-
48
- rclcpp::init (0 , nullptr );
49
- auto node_options = rclcpp::NodeOptions{};
50
- auto test_target_node = std::make_shared<ServiceLogChecker>(node_options);
51
- auto test_log = std::make_shared<PubManager>();
52
- ServiceLog log ;
53
- log .type = 6 ;
54
- log .name = " test" ;
55
- log .node = " test_node" ;
56
- test_log->pub_odom_ ->publish (log );
57
-
58
- while (!test_log->flag ) {
59
48
}
49
+ };
50
+
51
+ rclcpp::init (0 , nullptr );
52
+ auto node_options = rclcpp::NodeOptions{};
53
+ auto test_target_node = std::make_shared<ServiceLogChecker>(node_options);
54
+ auto test_log = std::make_shared<PubManager>();
55
+ ServiceLog log ;
56
+ log .type = 6 ;
57
+ log .name = " test" ;
58
+ log .node = " test_node" ;
59
+ test_log->pub_odom_ ->publish (log );
60
+
61
+ while (!test_log->flag ) {
62
+ }
60
63
}
0 commit comments