TestBotaDriverResetService.cpp
Go to the documentation of this file.
1 
7 #include <gtest/gtest.h>
8 #include <gtest/gtest-spi.h>
9 #include <geometry_msgs/WrenchStamped.h>
10 #include <geometry_msgs/Wrench.h>
11 #include <ros/ros.h>
12 #include <rokubimini_msgs/ResetWrench.h>
13 #include <Eigen/Dense>
14 
15 using namespace Eigen;
16 namespace bota_driver_testing
17 {
18 class BotaDriverTestResetService : public ::testing::Test
19 {
20 protected:
22  ros::NodeHandle nh_{ "~" };
23  std::uint32_t msgCount_;
24  geometry_msgs::Wrench meanWrenchOffset_;
25  std::string topicName_;
26  std::string serviceName_;
27  VectorXd fxSamples_;
28  VectorXd fySamples_;
29  VectorXd fzSamples_;
30  VectorXd txSamples_;
31  VectorXd tySamples_;
32  VectorXd tzSamples_;
33  double fx_, fy_, fz_, tx_, ty_, tz_;
34 
35  BotaDriverTestResetService() : msgCount_(0)
36  {
37  }
38 
40  {
41  // You can do clean-up work that doesn't throw exceptions here.
42  }
43 
44  // If the constructor and destructor are not enough for setting up
45  // and cleaning up each test, you can define the following methods:
46 
47  void SetUp() override
48  {
49  // Code here will be called immediately after the constructor (right
50  // before each test).
51  }
52 
53  void TearDown() override
54  {
55  // Code here will be called immediately after each test (right
56  // before the destructor).
57  }
58 
59 public:
60  void resetWrenchCallback(const geometry_msgs::WrenchStamped::ConstPtr& msg)
61  {
62  std::uint32_t lpos = msgCount_;
63  msgCount_++;
64  fxSamples_.conservativeResize(msgCount_);
65  fySamples_.conservativeResize(msgCount_);
66  fzSamples_.conservativeResize(msgCount_);
67  txSamples_.conservativeResize(msgCount_);
68  tySamples_.conservativeResize(msgCount_);
69  tzSamples_.conservativeResize(msgCount_);
70 
71  fxSamples_(lpos) = msg->wrench.force.x;
72  fySamples_(lpos) = msg->wrench.force.y;
73  fzSamples_(lpos) = msg->wrench.force.z;
74  txSamples_(lpos) = msg->wrench.torque.x;
75  tySamples_(lpos) = msg->wrench.torque.y;
76  tzSamples_(lpos) = msg->wrench.torque.z;
77  }
78 };
79 
81 {
82  SCOPED_TRACE("TestResetServiceCustomWrench");
83  ros::Time time_offset;
84  // add a small time offset for the serial to start
85  double starting_offset = 18.0;
86  double test_duration;
87  ASSERT_EQ(nh_.getParam("topic_name", topicName_), true);
88  ASSERT_EQ(nh_.getParam("service_name", serviceName_), true);
89  ASSERT_EQ(nh_.getParam("fx", fx_), true);
90  ASSERT_EQ(nh_.getParam("fy", fy_), true);
91  ASSERT_EQ(nh_.getParam("fz", fz_), true);
92  ASSERT_EQ(nh_.getParam("tx", tx_), true);
93  ASSERT_EQ(nh_.getParam("ty", ty_), true);
94  ASSERT_EQ(nh_.getParam("tz", tz_), true);
95  ASSERT_EQ(nh_.getParam("test_duration", test_duration), true);
96  ASSERT_GE(test_duration, starting_offset + 10.0);
97 
98  /*
99  * Step 1
100  * Create the previous offset of wrench.
101  *
102  */
103  time_offset = ros::Time::now() + ros::Duration(starting_offset);
104  while (ros::ok() && ros::Time::now() < time_offset)
105  {
106  ros::spinOnce();
107  if (HasFatalFailure())
108  {
109  FAIL() << "Fatal errors occurred.\n";
110  return;
111  }
112  }
113 
114  /*
115  * Step 2
116  * Call successfully the ros service (reset_wrench).
117  *
118  */
119  ASSERT_TRUE(ros::service::waitForService(serviceName_));
120  rokubimini_msgs::ResetWrench::Request req;
121  rokubimini_msgs::ResetWrench::Response res;
122  req.desired_wrench = geometry_msgs::Wrench();
123  req.desired_wrench.force.x = fx_;
124  req.desired_wrench.force.y = fy_;
125  req.desired_wrench.force.z = fz_;
126  req.desired_wrench.torque.x = tx_;
127  req.desired_wrench.torque.y = ty_;
128  req.desired_wrench.torque.z = tz_;
129  ASSERT_TRUE(ros::service::call(serviceName_, req, res));
130  EXPECT_EQ(res.success, true);
131 
132  /*
133  * Step 3
134  * Gather measurements to form the new mean offset of wrench.
135  *
136  */
137  sub_ = nh_.subscribe(topicName_, 1000, &BotaDriverTestResetService::resetWrenchCallback,
139  time_offset = ros::Time::now() + ros::Duration(test_duration - starting_offset);
140  while (ros::ok() && ros::Time::now() < time_offset)
141  {
142  ros::spinOnce();
143  if (HasFatalFailure())
144  {
145  FAIL() << "Fatal errors occurred.\n";
146  return;
147  }
148  }
149  meanWrenchOffset_.force.x = fxSamples_.mean();
150  meanWrenchOffset_.force.y = fySamples_.mean();
151  meanWrenchOffset_.force.z = fzSamples_.mean();
152  meanWrenchOffset_.torque.x = txSamples_.mean();
153  meanWrenchOffset_.torque.y = tySamples_.mean();
154  meanWrenchOffset_.torque.z = tzSamples_.mean();
155  ASSERT_GT(msgCount_, 0U);
156  EXPECT_NEAR(meanWrenchOffset_.force.x, fx_, 0.2);
157  EXPECT_NEAR(meanWrenchOffset_.force.y, fy_, 0.2);
158  EXPECT_NEAR(meanWrenchOffset_.force.z, fz_, 0.2);
159  EXPECT_NEAR(meanWrenchOffset_.torque.x, tx_, 0.01);
160  EXPECT_NEAR(meanWrenchOffset_.torque.y, ty_, 0.01);
161  EXPECT_NEAR(meanWrenchOffset_.torque.z, tz_, 0.01);
162 }
163 } // namespace bota_driver_testing
bota_driver_testing::BotaDriverTestResetService::serviceName_
std::string serviceName_
Definition: TestBotaDriverResetService.cpp:26
bota_driver_testing
Tests Command.
Definition: TestBotaDriverBoot.cpp:15
bota_driver_testing::BotaDriverTestResetService::tzSamples_
VectorXd tzSamples_
Definition: TestBotaDriverResetService.cpp:32
bota_driver_testing::BotaDriverTestResetService::tySamples_
VectorXd tySamples_
Definition: TestBotaDriverResetService.cpp:31
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
msg
msg
bota_driver_testing::BotaDriverTestResetService::msgCount_
std::uint32_t msgCount_
Definition: TestBotaDriverResetService.cpp:23
bota_driver_testing::BotaDriverTestResetService::TearDown
void TearDown() override
Definition: TestBotaDriverResetService.cpp:53
bota_driver_testing::BotaDriverTestResetService::fzSamples_
VectorXd fzSamples_
Definition: TestBotaDriverResetService.cpp:29
ros.h
bota_driver_testing::TEST_F
TEST_F(BotaDriverTestResetService, CustomWrench)
Definition: TestBotaDriverResetService.cpp:80
ros::spinOnce
ROSCPP_DECL void spinOnce()
bota_driver_testing::BotaDriverTestResetService::fySamples_
VectorXd fySamples_
Definition: TestBotaDriverResetService.cpp:28
bota_driver_testing::BotaDriverTestResetService::SetUp
void SetUp() override
Definition: TestBotaDriverResetService.cpp:47
ros::ok
ROSCPP_DECL bool ok()
bota_driver_testing::BotaDriverTestResetService::fxSamples_
VectorXd fxSamples_
Definition: TestBotaDriverResetService.cpp:27
bota_driver_testing::BotaDriverTestResetService
Definition: TestBotaDriverResetService.cpp:18
bota_driver_testing::BotaDriverTestResetService::sub_
ros::Subscriber sub_
Definition: TestBotaDriverResetService.cpp:21
bota_driver_testing::BotaDriverTestResetService::txSamples_
VectorXd txSamples_
Definition: TestBotaDriverResetService.cpp:30
bota_driver_testing::BotaDriverTestResetService::BotaDriverTestResetService
BotaDriverTestResetService()
Definition: TestBotaDriverResetService.cpp:35
bota_driver_testing::BotaDriverTestResetService::meanWrenchOffset_
geometry_msgs::Wrench meanWrenchOffset_
Definition: TestBotaDriverResetService.cpp:24
ros::Time
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
bota_driver_testing::BotaDriverTestResetService::tz_
double tz_
Definition: TestBotaDriverResetService.cpp:33
bota_driver_testing::BotaDriverTestResetService::topicName_
std::string topicName_
Definition: TestBotaDriverResetService.cpp:25
ros::Duration
ros::NodeHandle
ros::Subscriber
bota_driver_testing::BotaDriverTestResetService::resetWrenchCallback
void resetWrenchCallback(const geometry_msgs::WrenchStamped::ConstPtr &msg)
Definition: TestBotaDriverResetService.cpp:60
ros::Time::now
static Time now()
bota_driver_testing::BotaDriverTestResetService::~BotaDriverTestResetService
~BotaDriverTestResetService() override
Definition: TestBotaDriverResetService.cpp:39


bota_driver_testing
Author(s):
autogenerated on Sat Apr 15 2023 02:54:01