action_test_base.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2023, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef PLANNER_CSPACE_ACTION_TEST_BASE_H
31 #define PLANNER_CSPACE_ACTION_TEST_BASE_H
32 
33 #include <memory>
34 #include <string>
35 
36 #include <gtest/gtest.h>
37 
38 #include <ros/ros.h>
39 
41 #include <move_base_msgs/MoveBaseAction.h>
42 #include <nav_msgs/GetPlan.h>
43 #include <planner_cspace_msgs/PlannerStatus.h>
44 #include <tf2/utils.h>
46 
47 constexpr const char ACTION_TOPIC_MOVE_BASE[] = "/move_base";
48 constexpr const char ACTION_TOPIC_TOLERANT_MOVE[] = "/tolerant_move";
49 
50 template <typename ACTION, char const* TOPIC>
51 class ActionTestBase : public ::testing::Test
52 {
53 public:
55  : tfl_(tfbuf_)
56  , map_ready_(false)
57  {
58  move_base_ = std::make_shared<ActionClient>(TOPIC);
60  "/planner_3d/status", 10, &ActionTestBase::cbStatus, this);
61  }
62  void SetUp()
63  {
64  if (!move_base_->waitForServer(ros::Duration(30.0)))
65  {
66  FAIL() << "Failed to connect move_base action";
67  }
68 
69  ros::ServiceClient srv_plan =
70  node_.serviceClient<nav_msgs::GetPlanRequest, nav_msgs::GetPlanResponse>(
71  "/planner_3d/make_plan");
72 
73  const ros::Time deadline = ros::Time::now() + ros::Duration(10.0);
74  while (ros::ok())
75  {
76  nav_msgs::GetPlanRequest req;
77  nav_msgs::GetPlanResponse res;
78  req.tolerance = 10.0;
79  req.start.header.frame_id = "map";
80  req.start.pose.position.x = 1.24;
81  req.start.pose.position.y = 0.65;
82  req.start.pose.orientation.w = 1;
83  req.goal.header.frame_id = "map";
84  req.goal.pose.position.x = 1.25;
85  req.goal.pose.position.y = 0.75;
86  req.goal.pose.orientation.w = 1;
87  if (srv_plan.call(req, res))
88  {
89  // Planner is ready.
90  break;
91  }
92  if (ros::Time::now() > deadline)
93  {
94  FAIL() << "planner_3d didn't receive map";
95  }
96  ros::Duration(1).sleep();
97  ros::spinOnce();
98  }
99  }
101  {
102  }
103 
104 protected:
106  using ActionClientPtr = std::shared_ptr<ActionClient>;
107 
108  void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
109  {
111  }
112 
113  std::string statusString() const
114  {
115  if (!planner_status_)
116  {
117  return "(no status)";
118  }
119  return "(status: " + std::to_string(planner_status_->status) +
120  ", error: " + std::to_string(planner_status_->error) + ")";
121  }
122 
126  planner_cspace_msgs::PlannerStatus::ConstPtr planner_status_;
130 };
131 
132 #endif // PLANNER_CSPACE_ACTION_TEST_BASE_H
ActionTestBase::cbStatus
void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr &msg)
Definition: action_test_base.h:108
msg
msg
utils.h
ros.h
ActionTestBase::map_ready_
bool map_ready_
Definition: action_test_base.h:129
ACTION_TOPIC_TOLERANT_MOVE
constexpr const char ACTION_TOPIC_TOLERANT_MOVE[]
Definition: action_test_base.h:48
ActionTestBase< planner_cspace_msgs::MoveWithToleranceAction, ACTION_TOPIC_TOLERANT_MOVE >::ActionClientPtr
std::shared_ptr< ActionClient > ActionClientPtr
Definition: action_test_base.h:106
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::spinOnce
ROSCPP_DECL void spinOnce()
ActionTestBase::~ActionTestBase
~ActionTestBase()
Definition: action_test_base.h:100
ros::ok
ROSCPP_DECL bool ok()
tf2_ros::TransformListener
ActionTestBase::statusString
std::string statusString() const
Definition: action_test_base.h:113
ActionTestBase::tfl_
tf2_ros::TransformListener tfl_
Definition: action_test_base.h:128
actionlib::SimpleActionClient
ActionTestBase::planner_status_
planner_cspace_msgs::PlannerStatus::ConstPtr planner_status_
Definition: action_test_base.h:126
ActionTestBase::sub_status_
ros::Subscriber sub_status_
Definition: action_test_base.h:124
simple_action_client.h
ActionTestBase::tfbuf_
tf2_ros::Buffer tfbuf_
Definition: action_test_base.h:127
ActionTestBase::move_base_
ActionClientPtr move_base_
Definition: action_test_base.h:125
ros::ServiceClient
tf2_ros::Buffer
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
transform_listener.h
ros::Time
ActionTestBase::SetUp
void SetUp()
Definition: action_test_base.h:62
ACTION_TOPIC_MOVE_BASE
constexpr const char ACTION_TOPIC_MOVE_BASE[]
Definition: action_test_base.h:47
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ActionTestBase
Definition: action_test_base.h:51
ActionTestBase::ActionTestBase
ActionTestBase()
Definition: action_test_base.h:54
ros::Duration::sleep
bool sleep() const
ActionTestBase::node_
ros::NodeHandle node_
Definition: action_test_base.h:123
ros::Duration
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:22