25 #include "assisted_teleop_behavior_tester.hpp"
26 #include "nav2_util/geometry_utils.hpp"
28 using namespace std::chrono_literals;
29 using namespace std::chrono;
31 namespace nav2_system_tests
34 AssistedTeleopBehaviorTester::AssistedTeleopBehaviorTester()
36 initial_pose_received_(false)
38 node_ = rclcpp::Node::make_shared(
"assisted_teleop_behavior_test");
40 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
41 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
43 client_ptr_ = rclcpp_action::create_client<AssistedTeleop>(
44 node_->get_node_base_interface(),
45 node_->get_node_graph_interface(),
46 node_->get_node_logging_interface(),
47 node_->get_node_waitables_interface(),
51 node_->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"initialpose", 10);
54 node_->create_publisher<std_msgs::msg::Empty>(
"preempt_teleop", 10);
57 node_->create_publisher<geometry_msgs::msg::TwistStamped>(
"cmd_vel_teleop", 10);
59 subscription_ = node_->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
60 "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
61 std::bind(&AssistedTeleopBehaviorTester::amclPoseCallback,
this, std::placeholders::_1));
63 filtered_vel_sub_ = node_->create_subscription<geometry_msgs::msg::TwistStamped>(
65 rclcpp::SystemDefaultsQoS(),
66 std::bind(&AssistedTeleopBehaviorTester::filteredVelCallback,
this, std::placeholders::_1));
68 std::string costmap_topic =
"/local_costmap/costmap_raw";
69 std::string footprint_topic =
"/local_costmap/published_footprint";
71 costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
75 footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
80 collision_checker_ = std::make_unique<nav2_costmap_2d::CostmapTopicCollisionChecker>(
85 stamp_ = node_->now();
88 AssistedTeleopBehaviorTester::~AssistedTeleopBehaviorTester()
95 void AssistedTeleopBehaviorTester::activate()
98 throw std::runtime_error(
"Trying to activate while already active");
102 while (!initial_pose_received_) {
103 RCLCPP_WARN(node_->get_logger(),
"Initial pose not received");
105 std::this_thread::sleep_for(100ms);
106 rclcpp::spin_some(node_);
110 std::this_thread::sleep_for(10s);
113 RCLCPP_ERROR(node_->get_logger(),
"Action client not initialized");
118 if (!client_ptr_->wait_for_action_server(10s)) {
119 RCLCPP_ERROR(node_->get_logger(),
"Action server not available after waiting");
124 RCLCPP_INFO(this->node_->get_logger(),
"Assisted Teleop action server is ready");
128 void AssistedTeleopBehaviorTester::deactivate()
131 throw std::runtime_error(
"Trying to deactivate while already inactive");
136 bool AssistedTeleopBehaviorTester::defaultAssistedTeleopTest(
141 RCLCPP_ERROR(node_->get_logger(),
"Not activated");
145 RCLCPP_INFO(node_->get_logger(),
"Sending goal");
147 auto goal_handle_future = client_ptr_->async_send_goal(nav2_msgs::action::AssistedTeleop::Goal());
149 if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
150 rclcpp::FutureReturnCode::SUCCESS)
152 RCLCPP_ERROR(node_->get_logger(),
"send goal call failed :(");
156 rclcpp_action::ClientGoalHandle<AssistedTeleop>::SharedPtr goal_handle = goal_handle_future.get();
158 RCLCPP_ERROR(node_->get_logger(),
"Goal was rejected by server");
163 auto result_future = client_ptr_->async_get_result(goal_handle);
168 auto start_time = std::chrono::system_clock::now();
169 while (rclcpp::ok()) {
170 geometry_msgs::msg::TwistStamped cmd_vel = geometry_msgs::msg::TwistStamped();
171 cmd_vel.twist.linear.x = lin_vel;
172 cmd_vel.twist.angular.z = ang_vel;
173 cmd_vel_pub_->publish(cmd_vel);
179 auto current_time = std::chrono::system_clock::now();
180 if (current_time - start_time > 25s) {
181 RCLCPP_ERROR(node_->get_logger(),
"Exceeded Timeout");
185 rclcpp::spin_some(node_);
189 auto preempt_msg = std_msgs::msg::Empty();
190 preempt_pub_->publish(preempt_msg);
192 RCLCPP_INFO(node_->get_logger(),
"Waiting for result");
193 if (rclcpp::spin_until_future_complete(node_, result_future) !=
194 rclcpp::FutureReturnCode::SUCCESS)
196 RCLCPP_ERROR(node_->get_logger(),
"get result call failed :(");
200 rclcpp_action::ClientGoalHandle<AssistedTeleop>::WrappedResult
201 wrapped_result = result_future.get();
203 switch (wrapped_result.code) {
204 case rclcpp_action::ResultCode::SUCCEEDED:
break;
205 case rclcpp_action::ResultCode::ABORTED: RCLCPP_ERROR(
209 case rclcpp_action::ResultCode::CANCELED: RCLCPP_ERROR(
211 "Goal was canceled");
213 default: RCLCPP_ERROR(node_->get_logger(),
"Unknown result code");
217 RCLCPP_INFO(node_->get_logger(),
"result received");
219 geometry_msgs::msg::PoseStamped current_pose;
220 if (!nav2_util::getCurrentPose(current_pose, *tf_buffer_,
"odom")) {
221 RCLCPP_ERROR(node_->get_logger(),
"Current robot pose is not available.");
225 if (!collision_checker_->isCollisionFree(current_pose.pose)) {
226 RCLCPP_ERROR(node_->get_logger(),
"Ended in collision");
233 void AssistedTeleopBehaviorTester::sendInitialPose()
235 geometry_msgs::msg::PoseWithCovarianceStamped pose;
236 pose.header.frame_id =
"map";
237 pose.header.stamp = stamp_;
238 pose.pose.pose.position.x = -2.0;
239 pose.pose.pose.position.y = -0.5;
240 pose.pose.pose.position.z = 0.0;
241 pose.pose.pose.orientation.x = 0.0;
242 pose.pose.pose.orientation.y = 0.0;
243 pose.pose.pose.orientation.z = 0.0;
244 pose.pose.pose.orientation.w = 1.0;
245 for (
int i = 0; i < 35; i++) {
246 pose.pose.covariance[i] = 0.0;
248 pose.pose.covariance[0] = 0.08;
249 pose.pose.covariance[7] = 0.08;
250 pose.pose.covariance[35] = 0.05;
252 initial_pose_pub_->publish(pose);
253 RCLCPP_INFO(node_->get_logger(),
"Sent initial pose");
256 void AssistedTeleopBehaviorTester::amclPoseCallback(
257 const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr)
259 initial_pose_received_ =
true;
262 void AssistedTeleopBehaviorTester::filteredVelCallback(
263 geometry_msgs::msg::TwistStamped::SharedPtr msg)
265 if (msg->twist.linear.x == 0.0f) {