test/abstract_controller_execution.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <gmock/gmock.h>
3 #include <ros/ros.h>
4 
6 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
8 
9 #include <geometry_msgs/PoseStamped.h>
10 #include <geometry_msgs/TwistStamped.h>
11 #include <geometry_msgs/Twist.h>
12 #include <tf/transform_datatypes.h>
13 #include <geometry_msgs/TransformStamped.h>
14 
15 #include <string>
16 #include <vector>
17 
18 using geometry_msgs::PoseStamped;
19 using geometry_msgs::TransformStamped;
20 using geometry_msgs::Twist;
21 using geometry_msgs::TwistStamped;
24 using mbf_abstract_nav::MoveBaseFlexConfig;
25 using testing::_;
26 using testing::Return;
27 using testing::Test;
28 // for kinetic
30 
31 // the plan as a vector of poses
32 typedef std::vector<PoseStamped> plan_t;
33 
34 // mocked planner so we can control its output
36 {
37  // the mocked pure virtual members
38  MOCK_METHOD4(computeVelocityCommands, uint32_t(const PoseStamped&, const TwistStamped&, TwistStamped&, std::string&));
39  MOCK_METHOD2(isGoalReached, bool(double, double));
40  MOCK_METHOD1(setPlan, bool(const plan_t&));
41  MOCK_METHOD0(cancel, bool());
42 };
43 
46 
47 // fixture for our tests
49 {
52  TF_PTR, MoveBaseFlexConfig{})
53  {
54  }
55 
56  void TearDown() override
57  {
58  // after every test we expect that moving_ is set to false
59  // we don't expect this for the case NO_LOCAL_CMD
60  if (getState() != NO_LOCAL_CMD)
61  EXPECT_FALSE(isMoving());
62 
63  // we have to stop the thread when the test is done
64  join();
65  }
66 };
67 
69 {
70  // test checks the case where we call start() without setting a plan.
71  // the expected output is NO_PLAN.
72 
73  // start the controller
74  ASSERT_TRUE(start());
75 
76  // wait for the status update
77  waitForStateUpdate(boost::chrono::seconds(1));
78  ASSERT_EQ(getState(), NO_PLAN);
79 }
80 
82 {
83  // test checks the case where we pass an empty path to the controller.
84  // the expected output is EMPTY_PLAN
85 
86  // set an empty plan
87  setNewPlan(plan_t{}, true, 1, 1);
88 
89  // start the controller
90  ASSERT_TRUE(start());
91 
92  // wait for the status update
93  waitForStateUpdate(boost::chrono::seconds(1));
94  ASSERT_EQ(getState(), EMPTY_PLAN);
95 }
96 
98 {
99  // test checks the case where the controller recjets the plan.
100  // the expected output is INVALID_PLAN
101 
102  // setup the expectation: the controller rejects the plan
103  AbstractControllerMock& mock = dynamic_cast<AbstractControllerMock&>(*controller_);
104  EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(false));
105  // set a plan
106  plan_t plan(10);
107  setNewPlan(plan, true, 1, 1);
108 
109  // start the controller
110  ASSERT_TRUE(start());
111 
112  // wait for the status update
113  waitForStateUpdate(boost::chrono::seconds(1));
114  ASSERT_EQ(getState(), INVALID_PLAN);
115 }
116 
118 {
119  // test checks the case where we cannot compute the current robot pose
120  // the expected output is INTERNAL_ERROR
121 
122  // setup the expectation: the controller accepts the plan
123  AbstractControllerMock& mock = dynamic_cast<AbstractControllerMock&>(*controller_);
124  EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(true));
125 
126  // set a plan
127  plan_t plan(10);
128  setNewPlan(plan, true, 1, 1);
129 
130  // set the robot frame to some thing else then the global frame (for our test case)
131  global_frame_ = "global_frame";
132  robot_frame_ = "not_global_frame";
133 
134  // start the controller
135  ASSERT_TRUE(start());
136 
137  // wait for the status update
138  // note: this timeout must be larget then the default tf-timeout
139  waitForStateUpdate(boost::chrono::seconds(2));
140  ASSERT_EQ(getState(), INTERNAL_ERROR);
141 }
142 
143 // fixture making us pass computeRobotPose()
145 {
146  void SetUp()
147  {
148  // setup the transform.
149  global_frame_ = "global_frame";
150  robot_frame_ = "robot_frame";
151 #ifdef USE_OLD_TF
152  StampedTransform transform;
153  transform.child_frame_id_ = robot_frame_;
154  transform.frame_id_ = global_frame_;
155  transform.stamp_ = ros::Time::now();
156 #else
157  TransformStamped transform;
158  transform.header.stamp = ros::Time::now();
159  transform.header.frame_id = global_frame_;
160  transform.child_frame_id = robot_frame_;
161  transform.transform.rotation.w = 1;
162 #endif
163  // todo right now the mbf_utility checks on the transform age - but this does not work for static transforms
164  TF_PTR->setTransform(transform, "mama");
165  }
166 };
167 
169 {
170  // test checks the case where we reach the goal.
171  // the expected output is ARRIVED_GOAL
172 
173  // setup the expectation: the controller accepts the plan and says we are arrived
174  AbstractControllerMock& mock = dynamic_cast<AbstractControllerMock&>(*controller_);
175  EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(true));
176  EXPECT_CALL(mock, isGoalReached(_, _)).WillOnce(Return(true));
177 
178  // we compare against the back-pose of the plan
179  plan_t plan(10);
180  plan.back().header.frame_id = global_frame_;
181  plan.back().pose.orientation.w = 1;
182 
183  // make the toleraces small
184  setNewPlan(plan, true, 1e-3, 1e-3);
185 
186  // call start
187  ASSERT_TRUE(start());
188 
189  // wait for the status update
190  waitForStateUpdate(boost::chrono::seconds(1));
191  ASSERT_EQ(getState(), ARRIVED_GOAL);
192 }
193 
194 ACTION(ControllerException)
195 {
196  throw std::runtime_error("Oh no! Controller throws an Exception");
197 }
198 
199 TEST_F(ComputeRobotPoseFixture, controllerException)
200 {
201  // setup the expectation: the controller accepts the plan and says we are not arrived.
202  // the controller throws then an exception
203  AbstractControllerMock& mock = dynamic_cast<AbstractControllerMock&>(*controller_);
204  EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(true));
205  EXPECT_CALL(mock, isGoalReached(_, _)).WillOnce(Return(false));
206  EXPECT_CALL(mock, computeVelocityCommands(_, _, _, _)).WillOnce(ControllerException());
207 
208  // setup the plan
209  plan_t plan(10);
210  setNewPlan(plan, true, 1e-3, 1e-3);
211 
212  // call start
213  ASSERT_TRUE(start());
214 
215  // wait for the status update
216  waitForStateUpdate(boost::chrono::seconds(1));
217  ASSERT_EQ(getState(), INTERNAL_ERROR);
218 }
219 
220 // fixture which will setup the mock such that we generate a controller failure
222 {
223  void SetUp()
224  {
225  // setup the expectation: the controller accepts the plan and says we are not arrived.
226  // it furhermore returns an error code
227  AbstractControllerMock& mock = dynamic_cast<AbstractControllerMock&>(*controller_);
228  EXPECT_CALL(mock, setPlan(_)).WillOnce(Return(true));
229  EXPECT_CALL(mock, isGoalReached(_, _)).WillRepeatedly(Return(false));
230  EXPECT_CALL(mock, computeVelocityCommands(_, _, _, _)).WillRepeatedly(Return(11));
231 
232  // setup the plan
233  plan_t plan(10);
234  setNewPlan(plan, true, 1e-3, 1e-3);
235 
236  // call the parent method for the computeRobotPose call
238  }
239 };
240 
241 TEST_F(FailureFixture, maxRetries)
242 {
243  // test verifies the case where we exceed the max-retries.
244  // the expected output is MAX_RETRIES
245 
246  // enable the retries logic (max_retries > 0)
247  max_retries_ = 1;
248 
249  // call start
250  ASSERT_TRUE(start());
251 
252  // wait for the status update: in first iteration NO_LOCAL_CMD
253  waitForStateUpdate(boost::chrono::seconds(1));
254  ASSERT_EQ(getState(), NO_LOCAL_CMD);
255 
256  // wait for the status update: in second iteration MAX_RETRIES
257  // bcs max_retries_ > 0 && ++retries > max_retries_
258  waitForStateUpdate(boost::chrono::seconds(1));
259  ASSERT_EQ(getState(), MAX_RETRIES);
260 }
261 
262 TEST_F(FailureFixture, noValidCmd)
263 {
264  // test verfies the case where we don't exceed the patience or max-retries conditions
265  // the expected output is NO_VALID_CMD
266 
267  // disable the retries logic
268  max_retries_ = -1;
269  // call start
270  ASSERT_TRUE(start());
271 
272  // wait for the status update
273  waitForStateUpdate(boost::chrono::seconds(1));
274  ASSERT_EQ(getState(), NO_LOCAL_CMD);
275 }
276 
277 TEST_F(FailureFixture, patExceeded)
278 {
279  // test verfies the case where we exceed the patience
280  // the expected output is PAT_EXCEEDED
281 
282  // disable the retries logic and enable the patience logic: we cheat by setting it to a negative duration.
283  max_retries_ = -1;
284  patience_ = ros::Duration(-1e-3);
285 
286  // call start
287  ASSERT_TRUE(start());
288 
289  // wait for the status update
290  waitForStateUpdate(boost::chrono::seconds(1));
291  ASSERT_EQ(getState(), PAT_EXCEEDED);
292 }
293 
294 int main(int argc, char** argv)
295 {
296  ros::init(argc, argv, "read_types");
297  ros::NodeHandle nh;
298  // setup the pubs as global objects
299  VEL_PUB = nh.advertise<Twist>("vel", 1);
300  GOAL_PUB = nh.advertise<PoseStamped>("pose", 1);
301 
302  // setup the tf-publisher as a global object
303  TF_PTR.reset(new TF());
304  TF_PTR->setUsingDedicatedThread(true);
305 
306  // suppress the logging since we don't want warnings to polute the test-outcome
308  {
310  }
311  testing::InitGoogleTest(&argc, argv);
312  return RUN_ALL_TESTS();
313 }
AbstractControllerMock
Definition: test/abstract_controller_execution.cpp:35
tf::StampedTransform::stamp_
ros::Time stamp_
mbf_abstract_nav::AbstractExecutionBase::join
void join()
Definition: src/abstract_execution_base.cpp:76
ros::Publisher
boost::shared_ptr< tf::TransformListener >
mbf_abstract_nav::AbstractControllerExecution::getState
ControllerState getState() const
Return the current state of the controller execution. Thread communication safe.
Definition: src/abstract_controller_execution.cpp:126
mbf_abstract_core::AbstractController::cancel
virtual bool cancel()=0
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
AbstractControllerExecutionFixture::AbstractControllerExecutionFixture
AbstractControllerExecutionFixture()
Definition: test/abstract_controller_execution.cpp:50
tf::StampedTransform::child_frame_id_
std::string child_frame_id_
ros.h
ComputeRobotPoseFixture
Definition: test/abstract_controller_execution.cpp:144
main
int main(int argc, char **argv)
Definition: test/abstract_controller_execution.cpp:294
TEST_F
TEST_F(AbstractControllerExecutionFixture, noPlan)
Definition: test/abstract_controller_execution.cpp:68
VEL_PUB
ros::Publisher VEL_PUB
Definition: test/abstract_controller_execution.cpp:44
AbstractControllerExecutionFixture::TearDown
void TearDown() override
Definition: test/abstract_controller_execution.cpp:56
mbf_abstract_nav::AbstractControllerExecution::robot_frame_
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
Definition: abstract_controller_execution.h:245
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
tf::StampedTransform
tf::StampedTransform::frame_id_
std::string frame_id_
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ACTION
ACTION(ControllerException)
Definition: test/abstract_controller_execution.cpp:194
FailureFixture::SetUp
void SetUp()
Definition: test/abstract_controller_execution.cpp:223
AbstractControllerMock::MOCK_METHOD2
MOCK_METHOD2(isGoalReached, bool(double, double))
plan_t
std::vector< PoseStamped > plan_t
Definition: test/abstract_controller_execution.cpp:32
AbstractControllerExecutionFixture
Definition: test/abstract_controller_execution.cpp:48
abstract_controller_execution.h
AbstractControllerMock::MOCK_METHOD1
MOCK_METHOD1(setPlan, bool(const plan_t &))
ComputeRobotPoseFixture::SetUp
void SetUp()
Definition: test/abstract_controller_execution.cpp:146
AbstractControllerMock::MOCK_METHOD4
MOCK_METHOD4(computeVelocityCommands, uint32_t(const PoseStamped &, const TwistStamped &, TwistStamped &, std::string &))
GOAL_PUB
ros::Publisher GOAL_PUB
Definition: test/abstract_controller_execution.cpp:44
abstract_controller.h
EXPECT_CALL
EXPECT_CALL(action_server, publishResult(_, Field(&mbf_msgs::GetPathResult::outcome, Eq(mbf_msgs::GetPathResult::SUCCESS)))) .Times(1) .WillOnce(Notify(&done_condition_))
mbf_abstract_core::AbstractController::setPlan
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)=0
start
ROSCPP_DECL void start()
FailureFixture
Definition: test/abstract_controller_execution.cpp:221
mbf_abstract_nav::AbstractControllerExecution::global_frame_
std::string global_frame_
the global frame the robot is controlling in.
Definition: abstract_controller_execution.h:248
transform_datatypes.h
ros::console::levels::Fatal
Fatal
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
mbf_abstract_nav::AbstractControllerExecution::NO_LOCAL_CMD
@ NO_LOCAL_CMD
Received no velocity command by the plugin, in the current cycle.
Definition: abstract_controller_execution.h:144
mbf_abstract_core::AbstractController
tf::TransformListener
AbstractControllerMock::MOCK_METHOD0
MOCK_METHOD0(cancel, bool())
mbf_abstract_core::AbstractController::computeVelocityCommands
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)=0
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
mbf_abstract_nav::AbstractControllerExecution::setNewPlan
void setNewPlan(const std::vector< geometry_msgs::PoseStamped > &plan, bool tolerance_from_action=false, double action_dist_tolerance=1.0, double action_angle_tolerance=3.1415)
Sets a new plan to the controller execution.
Definition: src/abstract_controller_execution.cpp:132
mbf_abstract_nav::AbstractControllerExecution
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
Definition: abstract_controller_execution.h:75
ros::Duration
mbf_abstract_core::AbstractController::isGoalReached
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)=0
mbf_abstract_nav::AbstractControllerExecution::isMoving
bool isMoving() const
Returns whether the robot should normally move or not. True if the controller seems to work properly.
Definition: src/abstract_controller_execution.cpp:234
ros::NodeHandle
ros::Time::now
static Time now()
TF_PTR
TFPtr TF_PTR
Definition: test/abstract_controller_execution.cpp:45


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47