Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_cost_tool.cpp
1 // Copyright (c) 2024 Jatin Patil
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_rviz_plugins/costmap_cost_tool.hpp"
16 #include <rviz_common/viewport_mouse_event.hpp>
17 #include "rviz_common/display_context.hpp"
18 #include "rviz_common/load_resource.hpp"
19 #include "rviz_common/interaction/view_picker_iface.hpp"
20 #include "rviz_common/msg_conversions.hpp"
21 #include "rviz_common/properties/bool_property.hpp"
22 
23 namespace nav2_rviz_plugins
24 {
25 CostmapCostTool::CostmapCostTool()
26 : qos_profile_(5)
27 {
28  shortcut_key_ = 'm';
29 
30  auto_deactivate_property_ = new rviz_common::properties::BoolProperty(
31  "Single click", true,
32  "Switch away from this tool after one click.",
33  getPropertyContainer(), nullptr, this);
34 }
35 
36 CostmapCostTool::~CostmapCostTool() {}
37 
38 void CostmapCostTool::onInitialize()
39 {
40  hit_cursor_ = cursor_;
41  std_cursor_ = rviz_common::getDefaultCursor();
42 
43  setName("Costmap Cost");
44  setIcon(rviz_common::loadPixmap("package://rviz_default_plugins/icons/classes/PointStamped.png"));
45 
46  node_ptr_ = context_->getRosNodeAbstraction().lock();
47  if (node_ptr_ == nullptr) {
48  // The node no longer exists, so just don't initialize
49  RCLCPP_ERROR(
50  rclcpp::get_logger("costmap_cost_tool"),
51  "Underlying ROS node no longer exists, initialization failed");
52  return;
53  }
54  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
55  local_cost_client_ =
56  std::make_shared<nav2::ServiceClient<nav2_msgs::srv::GetCosts>>(
57  "local_costmap/get_cost_local_costmap",
58  node,
59  false /* Does not create and spin an internal executor*/);
60  global_cost_client_ =
61  std::make_shared<nav2::ServiceClient<nav2_msgs::srv::GetCosts>>(
62  "global_costmap/get_cost_global_costmap",
63  node,
64  false /* Does not create and spin an internal executor*/);
65 }
66 
67 void CostmapCostTool::activate() {}
68 void CostmapCostTool::deactivate() {}
69 
70 int CostmapCostTool::processMouseEvent(rviz_common::ViewportMouseEvent & event)
71 {
72  int flags = 0;
73 
74  Ogre::Vector3 position;
75  bool success = context_->getViewPicker()->get3DPoint(event.panel, event.x, event.y, position);
76  setCursor(success ? hit_cursor_ : std_cursor_);
77 
78  if (success) {
79  std::ostringstream s;
80  s << "<b>Left-Click:</b> Select this point.";
81  s.precision(3);
82  s << " [" << position.x << "," << position.y << "," << position.z << "]";
83  setStatus(s.str().c_str());
84 
85  if (event.leftUp()) {
86  auto point = rviz_common::pointOgreToMsg(position);
87 
88  callCostService(point.x, point.y);
89 
90  if (auto_deactivate_property_->getBool()) {
91  flags |= Finished;
92  }
93  }
94  } else {
95  setStatus("Move over an object to select the target point.");
96  }
97  return flags;
98 }
99 
100 void CostmapCostTool::callCostService(float x, float y)
101 {
102  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
103  // Create request for local costmap
104  auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
105  geometry_msgs::msg::PoseStamped pose;
106  pose.header.frame_id = context_->getFixedFrame().toStdString();
107  pose.header.stamp = node->now();
108  pose.pose.position.x = x;
109  pose.pose.position.y = y;
110  request->poses.push_back(pose);
111  request->use_footprint = false;
112 
113  // Call local costmap service
114  if (local_cost_client_->wait_for_service(std::chrono::seconds(1))) {
115  local_cost_client_->async_call(
116  request,
117  std::bind(&CostmapCostTool::handleLocalCostResponse, this, std::placeholders::_1));
118  }
119 
120  // Call global costmap service
121  if (global_cost_client_->wait_for_service(std::chrono::seconds(1))) {
122  global_cost_client_->async_call(
123  request,
124  std::bind(&CostmapCostTool::handleGlobalCostResponse, this, std::placeholders::_1));
125  }
126 }
127 
128 void CostmapCostTool::handleLocalCostResponse(
129  rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture future)
130 {
131  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
132  auto response = future.get();
133  RCLCPP_INFO(node->get_logger(), "Local costmap cost: %.1f", response->costs[0]);
134 }
135 
136 void CostmapCostTool::handleGlobalCostResponse(
137  rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture future)
138 {
139  rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
140  auto response = future.get();
141  RCLCPP_INFO(node->get_logger(), "Global costmap cost: %.1f", response->costs[0]);
142 }
143 } // namespace nav2_rviz_plugins
144 
145 #include <pluginlib/class_list_macros.hpp>
146 PLUGINLIB_EXPORT_CLASS(nav2_rviz_plugins::CostmapCostTool, rviz_common::Tool)