39 #ifndef RVIZ_VISUAL_TOOLS_IMARKER_SIMPLE_H 40 #define RVIZ_VISUAL_TOOLS_IMARKER_SIMPLE_H 45 #include <geometry_msgs/PoseStamped.h> 48 #include <visualization_msgs/InteractiveMarkerFeedback.h> 49 #include <visualization_msgs/InteractiveMarker.h> 51 #include <Eigen/Geometry> 58 using visualization_msgs::InteractiveMarkerFeedback;
59 using visualization_msgs::InteractiveMarkerControl;
61 typedef std::function<void(const visualization_msgs::InteractiveMarkerFeedbackConstPtr&)>
IMarkerCallback;
65 geometry_msgs::Pose getIdentityPose()
67 geometry_msgs::Pose pose;
68 pose.orientation.w = 1.0;
76 explicit IMarkerSimple(
const std::string& name =
"imarker",
double scale = 0.2,
77 const geometry_msgs::Pose& initial_pose = getIdentityPose());
81 void setPose(
const Eigen::Affine3d& pose);
83 void setPose(
const geometry_msgs::Pose& pose);
85 void iMarkerCallback(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
95 void make6DofMarker(
const geometry_msgs::Pose& pose,
double scale = 0.2);
100 std::string
name_ =
"imarker_simple";
123 #endif // RVIZ_VISUAL_TOOLS_IMARKER_SIMPLE_H