6 #ifndef VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERFEEDBACK_H
7 #define VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERFEEDBACK_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
25 template <
class ContainerAllocator>
59 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_client_id_type;
62 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_marker_name_type;
65 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_control_name_type;
71 typedef ::geometry_msgs::Pose_<ContainerAllocator>
_pose_type;
86 #if defined(_WIN32) && defined(KEEP_ALIVE)
89 #if defined(_WIN32) && defined(POSE_UPDATE)
92 #if defined(_WIN32) && defined(MENU_SELECT)
95 #if defined(_WIN32) && defined(BUTTON_CLICK)
98 #if defined(_WIN32) && defined(MOUSE_DOWN)
101 #if defined(_WIN32) && defined(MOUSE_UP)
115 typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator> >
Ptr;
116 typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator>
const>
ConstPtr;
141 template<
typename ContainerAllocator>
142 std::ostream&
operator<<(std::ostream& s, const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator> & v)
149 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
150 bool operator==(const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator1> & lhs, const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator2> & rhs)
152 return lhs.header == rhs.header &&
153 lhs.client_id == rhs.client_id &&
154 lhs.marker_name == rhs.marker_name &&
155 lhs.control_name == rhs.control_name &&
156 lhs.event_type == rhs.event_type &&
157 lhs.pose == rhs.pose &&
158 lhs.menu_entry_id == rhs.menu_entry_id &&
159 lhs.mouse_point == rhs.mouse_point &&
160 lhs.mouse_point_valid == rhs.mouse_point_valid;
163 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
164 bool operator!=(const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator1> & lhs, const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator2> & rhs)
166 return !(lhs == rhs);
174 namespace message_traits
181 template <
class ContainerAllocator>
186 template <
class ContainerAllocator>
191 template <
class ContainerAllocator>
196 template <
class ContainerAllocator>
201 template <
class ContainerAllocator>
206 template <
class ContainerAllocator>
212 template<
class ContainerAllocator>
217 return "ab0f1eee058667e28c19ff3ffc3f4b78";
220 static const char*
value(const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator>&) {
return value(); }
221 static const uint64_t static_value1 = 0xab0f1eee058667e2ULL;
222 static const uint64_t static_value2 = 0x8c19ff3ffc3f4b78ULL;
225 template<
class ContainerAllocator>
230 return "visualization_msgs/InteractiveMarkerFeedback";
233 static const char*
value(const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator>&) {
return value(); }
236 template<
class ContainerAllocator>
241 return "# Time/frame info.\n"
244 "# Identifying string. Must be unique in the topic namespace.\n"
247 "# Feedback message sent back from the GUI, e.g.\n"
248 "# when the status of an interactive marker was modified by the user.\n"
250 "# Specifies which interactive marker and control this message refers to\n"
251 "string marker_name\n"
252 "string control_name\n"
254 "# Type of the event\n"
255 "# KEEP_ALIVE: sent while dragging to keep up control of the marker\n"
256 "# MENU_SELECT: a menu entry has been selected\n"
257 "# BUTTON_CLICK: a button control has been clicked\n"
258 "# POSE_UPDATE: the pose has been changed using one of the controls\n"
259 "uint8 KEEP_ALIVE = 0\n"
260 "uint8 POSE_UPDATE = 1\n"
261 "uint8 MENU_SELECT = 2\n"
262 "uint8 BUTTON_CLICK = 3\n"
264 "uint8 MOUSE_DOWN = 4\n"
265 "uint8 MOUSE_UP = 5\n"
269 "# Current pose of the marker\n"
270 "# Note: Has to be valid for all feedback types.\n"
271 "geometry_msgs/Pose pose\n"
273 "# Contains the ID of the selected menu entry\n"
274 "# Only valid for MENU_SELECT events.\n"
275 "uint32 menu_entry_id\n"
277 "# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point\n"
278 "# may contain the 3 dimensional position of the event on the\n"
279 "# control. If it does, mouse_point_valid will be true. mouse_point\n"
280 "# will be relative to the frame listed in the header.\n"
281 "geometry_msgs/Point mouse_point\n"
282 "bool mouse_point_valid\n"
284 "================================================================================\n"
285 "MSG: std_msgs/Header\n"
286 "# Standard metadata for higher-level stamped data types.\n"
287 "# This is generally used to communicate timestamped data \n"
288 "# in a particular coordinate frame.\n"
290 "# sequence ID: consecutively increasing ID \n"
292 "#Two-integer timestamp that is expressed as:\n"
293 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
294 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
295 "# time-handling sugar is provided by the client library\n"
297 "#Frame this data is associated with\n"
300 "================================================================================\n"
301 "MSG: geometry_msgs/Pose\n"
302 "# A representation of pose in free space, composed of position and orientation. \n"
304 "Quaternion orientation\n"
306 "================================================================================\n"
307 "MSG: geometry_msgs/Point\n"
308 "# This contains the position of a point in free space\n"
313 "================================================================================\n"
314 "MSG: geometry_msgs/Quaternion\n"
315 "# This represents an orientation in free space in quaternion form.\n"
324 static const char*
value(const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator>&) {
return value(); }
332 namespace serialization
337 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
339 stream.next(m.header);
340 stream.next(m.client_id);
341 stream.next(m.marker_name);
342 stream.next(m.control_name);
343 stream.next(m.event_type);
345 stream.next(m.menu_entry_id);
346 stream.next(m.mouse_point);
347 stream.next(m.mouse_point_valid);
358 namespace message_operations
361 template<
class ContainerAllocator>
364 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::visualization_msgs::InteractiveMarkerFeedback_<ContainerAllocator>& v)
371 s <<
indent <<
"marker_name: ";
373 s <<
indent <<
"control_name: ";
380 s <<
indent <<
"menu_entry_id: ";
382 s <<
indent <<
"mouse_point: ";
385 s <<
indent <<
"mouse_point_valid: ";
393 #endif // VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERFEEDBACK_H