17#ifndef NAVMAP_RVIZ_PLUGIN__NAVMAP_POSE_TOOL_HPP_
18#define NAVMAP_RVIZ_PLUGIN__NAVMAP_POSE_TOOL_HPP_
24#include <OgreVector.h>
28#include "geometry_msgs/msg/point.hpp"
29#include "geometry_msgs/msg/quaternion.hpp"
31#include "rviz_common/tool.hpp"
32#include "rviz_rendering/viewport_projection_finder.hpp"
33#include "rviz_default_plugins/visibility_control.hpp"
59 virtual void onPoseSet(
double x,
double y,
double z,
double theta) = 0;
64 std::string designation,
65 geometry_msgs::msg::Point position,
66 geometry_msgs::msg::Quaternion orientation,
70 std::shared_ptr<rviz_rendering::Arrow>
arrow_;
84 int processMouseLeftButtonPressed(std::pair<bool, Ogre::Vector3> xy_plane_intersection);
85 int processMouseMoved(std::pair<bool, Ogre::Vector3> xy_plane_intersection);
86 int processMouseLeftButtonReleased();
87 void makeArrowVisibleAndSetOrientation(
double angle);
88 double calculateAngle(Ogre::Vector3 start_point, Ogre::Vector3 end_point);
Definition navmap_goal_tool.hpp:39
Definition navmap_pose_tool.hpp:36