src
TestBotaDriverBoot.cpp
Go to the documentation of this file.
1
7
#include <gtest/gtest.h>
8
9
#include <rosgraph_msgs/Log.h>
10
#include <geometry_msgs/WrenchStamped.h>
11
#include <geometry_msgs/Wrench.h>
12
#include <
ros/ros.h
>
13
#include <
ros/connection_manager.h
>
14
15
namespace
bota_driver_testing
16
{
17
class
BotaDriverTestBoot
:
public
::testing::Test
18
{
19
protected
:
20
ros::Subscriber
sub_
;
21
ros::NodeHandle
nh_
{
"~"
};
22
std::string
nodeName_
;
23
float
testDuration_
;
24
25
BotaDriverTestBoot
()
26
{
27
}
28
29
~BotaDriverTestBoot
()
override
30
{
31
// You can do clean-up work that doesn't throw exceptions here.
32
}
33
34
// If the constructor and destructor are not enough for setting up
35
// and cleaning up each test, you can define the following methods:
36
37
void
SetUp
()
override
38
{
39
// Code here will be called immediately after the constructor (right
40
// before each test).
41
}
42
43
void
TearDown
()
override
44
{
45
// Code here will be called immediately after each test (right
46
// before the destructor).
47
}
48
49
public
:
50
void
rosoutCallback
(
const
rosgraph_msgs::Log::ConstPtr& msg)
51
{
52
// Check that the message has not type ERROR || FATAL and the sender node is not rokubimini.
53
ASSERT_NE((
msg
->level == rosgraph_msgs::Log::ERROR ||
msg
->level == rosgraph_msgs::Log::FATAL) &&
54
msg
->name ==
nodeName_
,
55
true
);
56
}
57
};
58
59
TEST_F
(
BotaDriverTestBoot
, NoErrorsInBoot)
60
{
61
SCOPED_TRACE(
"NoErrorsInBoot"
);
62
ASSERT_EQ(nh_.getParam(
"node"
, nodeName_),
true
);
63
sub_ = nh_.subscribe(
"/rosout"
, 1000, &
BotaDriverTestBoot::rosoutCallback
, (
BotaDriverTestBoot
*)
this
);
64
EXPECT_EQ(sub_.getNumPublishers(), 1U);
65
ASSERT_EQ(nh_.getParam(
"test_duration"
, testDuration_),
true
);
66
ros::Time
time_after_boot =
ros::Time::now
() +
ros::Duration
(testDuration_);
67
while
(
ros::ok
() &&
ros::Time::now
() < time_after_boot)
68
{
69
ros::spinOnce
();
70
if
(HasFatalFailure())
71
{
72
FAIL() <<
"There were errors in the boot process.\nReceived message from rokubimini node with type ERROR or "
73
"FATAL."
;
74
return
;
75
}
76
}
77
}
78
79
// bool MESSAGE_RECEIVED_ONCE = false;
80
// void wrenchCallback(const geometry_msgs::WrenchStamped::ConstPtr& msg)
81
// {
82
// // Every frame should have the following data:
83
// // frame.data.forces[0] = 11.1;
84
// // frame.data.forces[1] = 22.2;
85
// // frame.data.forces[2] = 33.3;
86
// // frame.data.forces[3] = 44.4;
87
// // frame.data.forces[4] = 55.5;
88
// // frame.data.forces[5] = 66.6;
89
// MESSAGE_RECEIVED_ONCE = true;
90
// ASSERT_FLOAT_EQ(msg->wrench.force.x, 11.1);
91
// ASSERT_FLOAT_EQ(msg->wrench.force.y, 22.2);
92
// ASSERT_FLOAT_EQ(msg->wrench.force.z, 33.3);
93
// ASSERT_FLOAT_EQ(msg->wrench.torque.x, 44.4);
94
// ASSERT_FLOAT_EQ(msg->wrench.torque.y, 55.5);
95
// ASSERT_FLOAT_EQ(msg->wrench.torque.z, 66.6);
96
// }
97
98
// TEST_F(BotaDeviceDriverTest, CorrectSensorValuesInBoot)
99
// {
100
// SCOPED_TRACE("CorrectSensorValuesInBoot");
101
// sub_ = nh_.subscribe("/rokubimini/ft_sensor0/ft_sensor_readings/wrench", 1000,
102
// &bota_device_driver::wrenchCallback);
103
// // 30 seconds delay
104
// ros::Time time_after_boot = ros::Time::now() + ros::Duration(30);
105
// while (ros::ok() && ros::Time::now() < time_after_boot)
106
// {
107
// ros::spinOnce();
108
// if (HasFatalFailure())
109
// {
110
// FAIL() << "There were errors in the frame data.\nReceived invalid data from rokubimini node publisher.";
111
// return;
112
// }
113
// }
114
// ASSERT_EQ(MESSAGE_RECEIVED_ONCE, true);
115
// ros::shutdown();
116
// }
117
118
}
// namespace bota_driver_testing
bota_driver_testing
Tests Command.
Definition:
TestBotaDriverBoot.cpp:15
msg
msg
bota_driver_testing::BotaDriverTestBoot::nh_
ros::NodeHandle nh_
Definition:
TestBotaDriverBoot.cpp:21
bota_driver_testing::BotaDriverTestBoot
Definition:
TestBotaDriverBoot.cpp:17
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
connection_manager.h
bota_driver_testing::BotaDriverTestBoot::SetUp
void SetUp() override
Definition:
TestBotaDriverBoot.cpp:37
bota_driver_testing::BotaDriverTestBoot::BotaDriverTestBoot
BotaDriverTestBoot()
Definition:
TestBotaDriverBoot.cpp:25
ros::ok
ROSCPP_DECL bool ok()
bota_driver_testing::BotaDriverTestBoot::rosoutCallback
void rosoutCallback(const rosgraph_msgs::Log::ConstPtr &msg)
Definition:
TestBotaDriverBoot.cpp:50
bota_driver_testing::TEST_F
TEST_F(BotaDriverTestBoot, NoErrorsInBoot)
Definition:
TestBotaDriverBoot.cpp:59
ros::Time
bota_driver_testing::BotaDriverTestBoot::~BotaDriverTestBoot
~BotaDriverTestBoot() override
Definition:
TestBotaDriverBoot.cpp:29
bota_driver_testing::BotaDriverTestBoot::nodeName_
std::string nodeName_
Definition:
TestBotaDriverBoot.cpp:22
bota_driver_testing::BotaDriverTestBoot::TearDown
void TearDown() override
Definition:
TestBotaDriverBoot.cpp:43
bota_driver_testing::BotaDriverTestBoot::testDuration_
float testDuration_
Definition:
TestBotaDriverBoot.cpp:23
bota_driver_testing::BotaDriverTestBoot::sub_
ros::Subscriber sub_
Definition:
TestBotaDriverBoot.cpp:20
ros::Duration
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
bota_driver_testing
Author(s):
autogenerated on Sat Apr 15 2023 02:54:01