15 #ifndef NAV2_RVIZ_PLUGINS__COSTMAP_COST_TOOL_HPP_
16 #define NAV2_RVIZ_PLUGINS__COSTMAP_COST_TOOL_HPP_
20 #include <nav2_msgs/srv/get_costs.hpp>
21 #include <rviz_common/ros_integration/ros_node_abstraction_iface.hpp>
22 #include <rviz_common/tool.hpp>
23 #include <rviz_common/properties/bool_property.hpp>
24 #include <rviz_common/properties/qos_profile_property.hpp>
25 #include <rclcpp/rclcpp.hpp>
26 #include "nav2_ros_common/service_client.hpp"
28 namespace nav2_rviz_plugins
38 void onInitialize()
override;
39 void activate()
override;
40 void deactivate()
override;
42 int processMouseEvent(rviz_common::ViewportMouseEvent & event)
override;
44 void callCostService(
float x,
float y);
46 void handleLocalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture);
47 void handleGlobalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture);
52 nav2::ServiceClient<nav2_msgs::srv::GetCosts>::SharedPtr local_cost_client_;
53 nav2::ServiceClient<nav2_msgs::srv::GetCosts>::SharedPtr global_cost_client_;
55 std::shared_ptr<rviz_common::ros_integration::RosNodeAbstractionIface> node_ptr_;
59 rviz_common::properties::BoolProperty * auto_deactivate_property_;
60 rviz_common::properties::QosProfileProperty * qos_profile_property_;
62 rclcpp::QoS qos_profile_;