robot_interaction.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Adam Leeper */
36 
37 #pragma once
38 
39 #include <visualization_msgs/InteractiveMarkerFeedback.h>
40 #include <visualization_msgs/InteractiveMarker.h>
45 #include <boost/function.hpp>
46 #include <boost/thread.hpp>
47 #include <memory>
48 
49 // This is needed for legacy code that includes robot_interaction.h but not
50 // interaction_handler.h
52 
53 namespace interactive_markers
54 {
55 class InteractiveMarkerServer;
56 }
57 
58 namespace robot_interaction
59 {
60 MOVEIT_CLASS_FORWARD(InteractionHandler); // Defines InteractionHandlerPtr, ConstPtr, WeakPtr... etc
61 MOVEIT_CLASS_FORWARD(KinematicOptionsMap); // Defines KinematicOptionsMapPtr, ConstPtr, WeakPtr... etc
62 MOVEIT_CLASS_FORWARD(RobotInteraction); // Defines RobotInteractionPtr, ConstPtr, WeakPtr... etc
63 
64 // Manage interactive markers for controlling a robot state.
65 //
66 // The RobotInteraction class manages one or more InteractionHandler objects
67 // each of which maintains a set of interactive markers for manipulating one
68 // group of one RobotState.
69 //
70 // The group being manipulated is common to all InteractionHandler objects
71 // contained in a RobotInteraction instance.
73 {
74 public:
76  static const std::string INTERACTIVE_MARKER_TOPIC;
77 
78  RobotInteraction(const moveit::core::RobotModelConstPtr& robot_model, const std::string& ns = "");
79  virtual ~RobotInteraction();
80 
81  const std::string& getServerTopic() const
82  {
83  return topic_;
84  }
85 
97  void addActiveComponent(const InteractiveMarkerConstructorFn& construct, const ProcessFeedbackFn& process,
99  const std::string& name = "");
100 
109  void decideActiveComponents(const std::string& group);
110  void decideActiveComponents(const std::string& group, InteractionStyle::InteractionStyle style);
111 
114  void clear();
115 
121  void addInteractiveMarkers(const InteractionHandlerPtr& handler, const double marker_scale = 0.0);
122 
123  // Update pose of all interactive markers to match the handler's RobotState.
124  // Call this when the handler's RobotState changes.
125  void updateInteractiveMarkers(const InteractionHandlerPtr& handler);
126 
127  // True if markers are being shown for this handler.
128  bool showingMarkers(const InteractionHandlerPtr& handler);
129 
130  // Display all markers that have been added.
131  // This is needed after calls to addInteractiveMarkers() to publish the
132  // resulting markers so they get displayed. This call is not needed after
133  // calling updateInteractiveMarkers() which publishes the results itself.
135 
136  // Clear all interactive markers.
137  // This removes all interactive markers but does not affect which
138  // interactions are active. After this a call to publishInteractiveMarkers()
139  // is needed to actually remove the markers from the display.
141 
142  const moveit::core::RobotModelConstPtr& getRobotModel() const
143  {
144  return robot_model_;
145  }
146 
147  // Get the kinematic options map.
148  // Use this to set kinematic options (defaults or per-group).
149  KinematicOptionsMapPtr getKinematicOptionsMap()
150  {
151  return kinematic_options_map_;
152  }
153 
154  // enable/disable subscription of the topics to move interactive marker
155  void toggleMoveInteractiveMarkerTopic(bool enable);
156 
157  const std::vector<EndEffectorInteraction>& getActiveEndEffectors() const
158  {
159  return active_eef_;
160  }
161  const std::vector<JointInteraction>& getActiveJoints() const
162  {
163  return active_vj_;
164  }
165 
166 private:
167  // called by decideActiveComponents(); add markers for end effectors
168  void decideActiveEndEffectors(const std::string& group);
169  void decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style);
170 
171  // called by decideActiveComponents(); add markers for planar and floating joints
172  void decideActiveJoints(const std::string& group);
173 
174  void moveInteractiveMarker(const std::string& name, const geometry_msgs::PoseStamped& msg);
175  // register the name of the topic and marker name to move interactive marker from other ROS nodes
176  void registerMoveInteractiveMarkerTopic(const std::string& marker_name, const std::string& name);
177  // return the diameter of the sphere that certainly can enclose the AABB of the link
178  double computeLinkMarkerSize(const std::string& link);
179  // return the diameter of the sphere that certainly can enclose the AABB of the links in this group
180  double computeGroupMarkerSize(const std::string& group);
181  void computeMarkerPose(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
182  const moveit::core::RobotState& robot_state, geometry_msgs::Pose& pose,
183  geometry_msgs::Pose& control_to_eef_tf) const;
184 
185  void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
186  visualization_msgs::InteractiveMarker& im, bool position = true, bool orientation = true);
187  void addEndEffectorMarkers(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
188  const geometry_msgs::Pose& offset, visualization_msgs::InteractiveMarker& im,
189  bool position = true, bool orientation = true);
190  void processInteractiveMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback);
191  void subscribeMoveInteractiveMarker(const std::string marker_name, const std::string& name);
192  void processingThread();
194 
195  std::unique_ptr<boost::thread> processing_thread_;
197 
198  boost::condition_variable new_feedback_condition_;
199  std::map<std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr> feedback_map_;
200 
201  moveit::core::RobotModelConstPtr robot_model_;
202 
203  std::vector<EndEffectorInteraction> active_eef_;
204  std::vector<JointInteraction> active_vj_;
205  std::vector<GenericInteraction> active_generic_;
206 
207  std::map<std::string, InteractionHandlerPtr> handlers_;
208  std::map<std::string, std::size_t> shown_markers_;
209 
210  // This mutex is locked every time markers are read or updated;
211  // This includes the active_* arrays and shown_markers_
212  // Please note that this mutex *MUST NOT* be locked while operations
213  // on the interative marker server are called because the server
214  // also locks internally and we could othewrise end up with a problem
215  // of Thread 1: Lock A, Lock B, Unlock B, Unloack A
216  // Thread 2: Lock B, Lock A
217  // => deadlock
218  boost::mutex marker_access_lock_;
219 
221  // ros subscribers to move the interactive markers by other ros nodes
222  std::vector<ros::Subscriber> int_marker_move_subscribers_;
223  // the array of the names of the topics which need to be subscribed
224  // to move the interactive markers by other ROS nodes
225  std::vector<std::string> int_marker_move_topics_;
226  // the array of the marker names in the same order to int_marker_move_topics_
227  std::vector<std::string> int_marker_names_;
228 
229  std::string topic_;
230 
231  // options for doing IK
232  KinematicOptionsMapPtr kinematic_options_map_;
233 };
234 } // namespace robot_interaction
robot_interaction::RobotInteraction::toggleMoveInteractiveMarkerTopic
void toggleMoveInteractiveMarkerTopic(bool enable)
Definition: robot_interaction.cpp:594
robot_interaction::RobotInteraction::INTERACTIVE_MARKER_TOPIC
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
Definition: robot_interaction.h:76
robot_interaction::RobotInteraction::clear
void clear()
Definition: robot_interaction.cpp:380
robot_interaction::RobotInteraction::decideActiveEndEffectors
void decideActiveEndEffectors(const std::string &group)
Definition: robot_interaction.cpp:288
robot_interaction::RobotInteraction::RobotInteraction
RobotInteraction(const moveit::core::RobotModelConstPtr &robot_model, const std::string &ns="")
Definition: robot_interaction.cpp:98
robot_interaction::RobotInteraction::registerMoveInteractiveMarkerTopic
void registerMoveInteractiveMarkerTopic(const std::string &marker_name, const std::string &name)
Definition: robot_interaction.cpp:585
robot_interaction::RobotInteraction::getKinematicOptionsMap
KinematicOptionsMapPtr getKinematicOptionsMap()
Definition: robot_interaction.h:149
robot_interaction::RobotInteraction::int_marker_move_subscribers_
std::vector< ros::Subscriber > int_marker_move_subscribers_
Definition: robot_interaction.h:222
robot_interaction::RobotInteraction::processInteractiveMarkerFeedback
void processInteractiveMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Definition: robot_interaction.cpp:730
robot_interaction::RobotInteraction::marker_access_lock_
boost::mutex marker_access_lock_
Definition: robot_interaction.h:218
robot_interaction::RobotInteraction::decideActiveComponents
void decideActiveComponents(const std::string &group)
Definition: robot_interaction.cpp:119
menu_handler.h
robot_interaction::RobotInteraction::handlers_
std::map< std::string, InteractionHandlerPtr > handlers_
Definition: robot_interaction.h:207
moveit::core::RobotState
robot_interaction::RobotInteraction::feedback_map_
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
Definition: robot_interaction.h:199
robot_state.h
robot_interaction::RobotInteraction::decideActiveJoints
void decideActiveJoints(const std::string &group)
Definition: robot_interaction.cpp:217
robot_interaction::RobotInteraction::updateInteractiveMarkers
void updateInteractiveMarkers(const InteractionHandlerPtr &handler)
Definition: robot_interaction.cpp:649
robot_interaction::RobotInteraction::processingThread
void processingThread()
Definition: robot_interaction.cpp:753
robot_interaction::InteractiveMarkerUpdateFn
boost::function< bool(const moveit::core::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
Definition: interaction.h:114
interaction_handler.h
robot_interaction::InteractionStyle::InteractionStyle
InteractionStyle
Definition: interaction.h:60
robot_interaction::InteractiveMarkerConstructorFn
boost::function< bool(const moveit::core::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
Definition: interaction.h:88
interaction.h
robot_interaction::RobotInteraction::computeMarkerPose
void computeMarkerPose(const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const moveit::core::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const
Definition: robot_interaction.cpp:620
robot_interaction::RobotInteraction::addActiveComponent
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
Definition: robot_interaction.cpp:135
robot_interaction::RobotInteraction::active_generic_
std::vector< GenericInteraction > active_generic_
Definition: robot_interaction.h:205
robot_interaction::RobotInteraction::getActiveJoints
const std::vector< JointInteraction > & getActiveJoints() const
Definition: robot_interaction.h:161
robot_interaction::RobotInteraction::int_marker_server_
interactive_markers::InteractiveMarkerServer * int_marker_server_
Definition: robot_interaction.h:220
robot_interaction::RobotInteraction::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: robot_interaction.h:142
robot_interaction::RobotInteraction::showingMarkers
bool showingMarkers(const InteractionHandlerPtr &handler)
Definition: robot_interaction.cpp:695
robot_interaction::RobotInteraction::int_marker_names_
std::vector< std::string > int_marker_names_
Definition: robot_interaction.h:227
robot_interaction::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(InteractionHandler)
robot_interaction::RobotInteraction::processing_thread_
std::unique_ptr< boost::thread > processing_thread_
Definition: robot_interaction.h:195
robot_interaction::RobotInteraction::getActiveEndEffectors
const std::vector< EndEffectorInteraction > & getActiveEndEffectors() const
Definition: robot_interaction.h:157
robot_interaction::RobotInteraction::run_processing_thread_
bool run_processing_thread_
Definition: robot_interaction.h:196
robot_interaction::RobotInteraction::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: robot_interaction.h:201
robot_interaction::RobotInteraction
Definition: robot_interaction.h:72
robot_interaction::RobotInteraction::clearInteractiveMarkersUnsafe
void clearInteractiveMarkersUnsafe()
Definition: robot_interaction.cpp:396
robot_interaction::RobotInteraction::getServerTopic
const std::string & getServerTopic() const
Definition: robot_interaction.h:81
robot_interaction::RobotInteraction::clearInteractiveMarkers
void clearInteractiveMarkers()
Definition: robot_interaction.cpp:390
robot_interaction::RobotInteraction::int_marker_move_topics_
std::vector< std::string > int_marker_move_topics_
Definition: robot_interaction.h:225
interactive_markers::InteractiveMarkerServer
robot_interaction::EndEffectorInteraction
Definition: interaction.h:139
robot_interaction::RobotInteraction::publishInteractiveMarkers
void publishInteractiveMarkers()
Definition: robot_interaction.cpp:689
robot_interaction::RobotInteraction::computeLinkMarkerSize
double computeLinkMarkerSize(const std::string &link)
Definition: robot_interaction.cpp:150
robot_interaction::ProcessFeedbackFn
boost::function< bool(moveit::core::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
Definition: interaction.h:103
robot_interaction::RobotInteraction::active_eef_
std::vector< EndEffectorInteraction > active_eef_
Definition: robot_interaction.h:203
class_forward.h
robot_interaction::RobotInteraction::addEndEffectorMarkers
void addEndEffectorMarkers(const InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
Definition: robot_interaction.cpp:406
robot_interaction::RobotInteraction::kinematic_options_map_
KinematicOptionsMapPtr kinematic_options_map_
Definition: robot_interaction.h:232
robot_interaction::RobotInteraction::subscribeMoveInteractiveMarker
void subscribeMoveInteractiveMarker(const std::string marker_name, const std::string &name)
robot_interaction::RobotInteraction::computeGroupMarkerSize
double computeGroupMarkerSize(const std::string &group)
Definition: robot_interaction.cpp:180
robot_interaction
Definition: interaction.h:54
robot_interaction::RobotInteraction::shown_markers_
std::map< std::string, std::size_t > shown_markers_
Definition: robot_interaction.h:208
interactive_markers
robot_interaction::RobotInteraction::new_feedback_condition_
boost::condition_variable new_feedback_condition_
Definition: robot_interaction.h:198
robot_interaction::RobotInteraction::topic_
std::string topic_
Definition: robot_interaction.h:229
robot_interaction::RobotInteraction::moveInteractiveMarker
void moveInteractiveMarker(const std::string &name, const geometry_msgs::PoseStamped &msg)
Definition: robot_interaction.cpp:711
robot_interaction::RobotInteraction::~RobotInteraction
virtual ~RobotInteraction()
Definition: robot_interaction.cpp:109
robot_interaction::RobotInteraction::addInteractiveMarkers
void addInteractiveMarkers(const InteractionHandlerPtr &handler, const double marker_scale=0.0)
Definition: robot_interaction.cpp:482
robot_interaction::RobotInteraction::active_vj_
std::vector< JointInteraction > active_vj_
Definition: robot_interaction.h:204


robot_interaction
Author(s): Ioan Sucan
autogenerated on Sat Mar 15 2025 02:26:54