15 #ifndef NAV2_RVIZ_PLUGINS__COSTMAP_COST_TOOL_HPP_
16 #define NAV2_RVIZ_PLUGINS__COSTMAP_COST_TOOL_HPP_
18 #include <nav2_msgs/srv/get_cost.hpp>
19 #include <rviz_common/tool.hpp>
20 #include <rviz_default_plugins/tools/point/point_tool.hpp>
21 #include <rclcpp/rclcpp.hpp>
23 namespace nav2_rviz_plugins
33 void onInitialize()
override;
34 void activate()
override;
35 void deactivate()
override;
37 int processMouseEvent(rviz_common::ViewportMouseEvent & event)
override;
39 void callCostService(
float x,
float y);
41 void handleLocalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture);
42 void handleGlobalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture);
45 void updateAutoDeactivate();
48 rclcpp::Client<nav2_msgs::srv::GetCost>::SharedPtr local_cost_client_;
49 rclcpp::Client<nav2_msgs::srv::GetCost>::SharedPtr global_cost_client_;
50 rclcpp::Node::SharedPtr node_;
54 rviz_common::properties::BoolProperty * auto_deactivate_property_;
55 rviz_common::properties::QosProfileProperty * qos_profile_property_;
57 rclcpp::QoS qos_profile_;