interaction_handler.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012-2013, Willow Garage, Inc.
00005  *  Copyright (c) 2013, Ioan A. Sucan
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /* Author: Ioan Sucan, Adam Leeper */
00037 
00038 #include <moveit/robot_interaction/interaction_handler.h>
00039 #include <moveit/robot_interaction/robot_interaction.h>
00040 #include <moveit/robot_interaction/interactive_marker_helpers.h>
00041 #include <moveit/robot_interaction/kinematic_options_map.h>
00042 #include <moveit/transforms/transforms.h>
00043 #include <interactive_markers/interactive_marker_server.h>
00044 #include <interactive_markers/menu_handler.h>
00045 #include <eigen_conversions/eigen_msg.h>
00046 #include <tf_conversions/tf_eigen.h>
00047 #include <boost/lexical_cast.hpp>
00048 #include <boost/math/constants/constants.hpp>
00049 #include <algorithm>
00050 #include <limits>
00051 
00052 #include <Eigen/Core>
00053 #include <Eigen/Geometry>
00054 
00055 namespace robot_interaction
00056 {
00057 InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
00058                                        const robot_state::RobotState& initial_robot_state,
00059                                        const boost::shared_ptr<tf::Transformer>& tf)
00060   : LockedRobotState(initial_robot_state)
00061   , name_(fixName(name))
00062   , planning_frame_(initial_robot_state.getRobotModel()->getModelFrame())
00063   , tf_(tf)
00064   , robot_interaction_(NULL)
00065   , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
00066   , display_meshes_(true)
00067   , display_controls_(true)
00068 {
00069   setRobotInteraction(robot_interaction.get());
00070 }
00071 
00072 InteractionHandler::InteractionHandler(const RobotInteractionPtr& robot_interaction, const std::string& name,
00073                                        const boost::shared_ptr<tf::Transformer>& tf)
00074   : LockedRobotState(robot_interaction->getRobotModel())
00075   , name_(fixName(name))
00076   , planning_frame_(robot_interaction->getRobotModel()->getModelFrame())
00077   , tf_(tf)
00078   , robot_interaction_(NULL)
00079   , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
00080   , display_meshes_(true)
00081   , display_controls_(true)
00082 {
00083   setRobotInteraction(robot_interaction.get());
00084 }
00085 
00086 // DEPRECATED
00087 InteractionHandler::InteractionHandler(const std::string& name, const robot_state::RobotState& initial_robot_state,
00088                                        const boost::shared_ptr<tf::Transformer>& tf)
00089   : LockedRobotState(initial_robot_state)
00090   , name_(fixName(name))
00091   , planning_frame_(initial_robot_state.getRobotModel()->getModelFrame())
00092   , tf_(tf)
00093   , robot_interaction_(NULL)
00094   , kinematic_options_map_(new KinematicOptionsMap)
00095   , display_meshes_(true)
00096   , display_controls_(true)
00097 {
00098 }
00099 
00100 // DEPRECATED
00101 InteractionHandler::InteractionHandler(const std::string& name, const robot_model::RobotModelConstPtr& robot_model,
00102                                        const boost::shared_ptr<tf::Transformer>& tf)
00103   : LockedRobotState(robot_model)
00104   , name_(fixName(name))
00105   , planning_frame_(robot_model->getModelFrame())
00106   , tf_(tf)
00107   , robot_interaction_(NULL)
00108   , kinematic_options_map_(new KinematicOptionsMap)
00109   , display_meshes_(true)
00110   , display_controls_(true)
00111 {
00112 }
00113 
00114 std::string InteractionHandler::fixName(std::string name)
00115 {
00116   std::replace(name.begin(), name.end(), '_', '-');  // we use _ as a special char in marker name
00117   return name;
00118 }
00119 
00120 void InteractionHandler::setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::Pose& m)
00121 {
00122   boost::mutex::scoped_lock slock(offset_map_lock_);
00123   offset_map_[eef.eef_group] = m;
00124 }
00125 
00126 void InteractionHandler::setPoseOffset(const JointInteraction& vj, const geometry_msgs::Pose& m)
00127 {
00128   boost::mutex::scoped_lock slock(offset_map_lock_);
00129   offset_map_[vj.joint_name] = m;
00130 }
00131 
00132 void InteractionHandler::clearPoseOffset(const EndEffectorInteraction& eef)
00133 {
00134   boost::mutex::scoped_lock slock(offset_map_lock_);
00135   offset_map_.erase(eef.eef_group);
00136 }
00137 
00138 void InteractionHandler::clearPoseOffset(const JointInteraction& vj)
00139 {
00140   boost::mutex::scoped_lock slock(offset_map_lock_);
00141   offset_map_.erase(vj.joint_name);
00142 }
00143 
00144 void InteractionHandler::clearPoseOffsets()
00145 {
00146   boost::mutex::scoped_lock slock(offset_map_lock_);
00147   offset_map_.clear();
00148 }
00149 
00150 bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::Pose& m)
00151 {
00152   boost::mutex::scoped_lock slock(offset_map_lock_);
00153   std::map<std::string, geometry_msgs::Pose>::iterator it = offset_map_.find(eef.eef_group);
00154   if (it != offset_map_.end())
00155   {
00156     m = it->second;
00157     return true;
00158   }
00159   return false;
00160 }
00161 
00162 bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs::Pose& m)
00163 {
00164   boost::mutex::scoped_lock slock(offset_map_lock_);
00165   std::map<std::string, geometry_msgs::Pose>::iterator it = offset_map_.find(vj.joint_name);
00166   if (it != offset_map_.end())
00167   {
00168     m = it->second;
00169     return true;
00170   }
00171   return false;
00172 }
00173 
00174 bool InteractionHandler::getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef, geometry_msgs::PoseStamped& ps)
00175 {
00176   boost::mutex::scoped_lock slock(pose_map_lock_);
00177   std::map<std::string, geometry_msgs::PoseStamped>::iterator it = pose_map_.find(eef.eef_group);
00178   if (it != pose_map_.end())
00179   {
00180     ps = it->second;
00181     return true;
00182   }
00183   return false;
00184 }
00185 
00186 bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::PoseStamped& ps)
00187 {
00188   boost::mutex::scoped_lock slock(pose_map_lock_);
00189   std::map<std::string, geometry_msgs::PoseStamped>::iterator it = pose_map_.find(vj.joint_name);
00190   if (it != pose_map_.end())
00191   {
00192     ps = it->second;
00193     return true;
00194   }
00195   return false;
00196 }
00197 
00198 void InteractionHandler::clearLastEndEffectorMarkerPose(const EndEffectorInteraction& eef)
00199 {
00200   boost::mutex::scoped_lock slock(pose_map_lock_);
00201   pose_map_.erase(eef.eef_group);
00202 }
00203 
00204 void InteractionHandler::clearLastJointMarkerPose(const JointInteraction& vj)
00205 {
00206   boost::mutex::scoped_lock slock(pose_map_lock_);
00207   pose_map_.erase(vj.joint_name);
00208 }
00209 
00210 void InteractionHandler::clearLastMarkerPoses()
00211 {
00212   boost::mutex::scoped_lock slock(pose_map_lock_);
00213   pose_map_.clear();
00214 }
00215 
00216 void InteractionHandler::setMenuHandler(const boost::shared_ptr<interactive_markers::MenuHandler>& mh)
00217 {
00218   boost::mutex::scoped_lock lock(state_lock_);
00219   menu_handler_ = mh;
00220 }
00221 
00222 const boost::shared_ptr<interactive_markers::MenuHandler>& InteractionHandler::getMenuHandler()
00223 {
00224   boost::mutex::scoped_lock lock(state_lock_);
00225   return menu_handler_;
00226 }
00227 
00228 void InteractionHandler::clearMenuHandler()
00229 {
00230   boost::mutex::scoped_lock lock(state_lock_);
00231   menu_handler_.reset();
00232 }
00233 
00234 void InteractionHandler::handleGeneric(const GenericInteraction& g,
00235                                        const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
00236 {
00237   if (g.process_feedback)
00238   {
00239     StateChangeCallbackFn callback;
00240     // modify the RobotState in-place with the state_lock_ held.
00241     LockedRobotState::modifyState(
00242         boost::bind(&InteractionHandler::updateStateGeneric, this, _1, &g, &feedback, &callback));
00243 
00244     // This calls update_callback_ to notify client that state changed.
00245     if (callback)
00246       callback(this);
00247   }
00248 }
00249 
00250 void InteractionHandler::handleEndEffector(const EndEffectorInteraction& eef,
00251                                            const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
00252 {
00253   if (feedback->event_type != visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
00254     return;
00255 
00256   geometry_msgs::PoseStamped tpose;
00257   geometry_msgs::Pose offset;
00258   if (!getPoseOffset(eef, offset))
00259     offset.orientation.w = 1;
00260   if (transformFeedbackPose(feedback, offset, tpose))
00261   {
00262     pose_map_lock_.lock();
00263     pose_map_[eef.eef_group] = tpose;
00264     pose_map_lock_.unlock();
00265   }
00266   else
00267     return;
00268 
00269   StateChangeCallbackFn callback;
00270 
00271   // modify the RobotState in-place with state_lock_ held.
00272   // This locks state_lock_ before calling updateState()
00273   LockedRobotState::modifyState(
00274       boost::bind(&InteractionHandler::updateStateEndEffector, this, _1, &eef, &tpose.pose, &callback));
00275 
00276   // This calls update_callback_ to notify client that state changed.
00277   if (callback)
00278     callback(this);
00279 }
00280 
00281 void InteractionHandler::handleJoint(const JointInteraction& vj,
00282                                      const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
00283 {
00284   if (feedback->event_type != visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
00285     return;
00286 
00287   geometry_msgs::PoseStamped tpose;
00288   geometry_msgs::Pose offset;
00289   if (!getPoseOffset(vj, offset))
00290     offset.orientation.w = 1;
00291   if (transformFeedbackPose(feedback, offset, tpose))
00292   {
00293     pose_map_lock_.lock();
00294     pose_map_[vj.joint_name] = tpose;
00295     pose_map_lock_.unlock();
00296   }
00297   else
00298     return;
00299 
00300   StateChangeCallbackFn callback;
00301 
00302   // modify the RobotState in-place with state_lock_ held.
00303   // This locks state_lock_ before calling updateState()
00304   LockedRobotState::modifyState(
00305       boost::bind(&InteractionHandler::updateStateJoint, this, _1, &vj, &tpose.pose, &callback));
00306 
00307   // This calls update_callback_ to notify client that state changed.
00308   if (callback)
00309     callback(this);
00310 }
00311 
00312 // MUST hold state_lock_ when calling this!
00313 void InteractionHandler::updateStateGeneric(robot_state::RobotState* state, const GenericInteraction* g,
00314                                             const visualization_msgs::InteractiveMarkerFeedbackConstPtr* feedback,
00315                                             StateChangeCallbackFn* callback)
00316 {
00317   bool ok = g->process_feedback(*state, *feedback);
00318   bool error_state_changed = setErrorState(g->marker_name_suffix, !ok);
00319   if (update_callback_)
00320     *callback = boost::bind(update_callback_, _1, error_state_changed);
00321 }
00322 
00323 // MUST hold state_lock_ when calling this!
00324 void InteractionHandler::updateStateEndEffector(robot_state::RobotState* state, const EndEffectorInteraction* eef,
00325                                                 const geometry_msgs::Pose* pose, StateChangeCallbackFn* callback)
00326 {
00327   // This is called with state_lock_ held, so no additional locking needed to
00328   // access kinematic_options_map_.
00329   KinematicOptions kinematic_options = kinematic_options_map_->getOptions(eef->parent_group);
00330 
00331   bool ok = kinematic_options.setStateFromIK(*state, eef->parent_group, eef->parent_link, *pose);
00332   bool error_state_changed = setErrorState(eef->parent_group, !ok);
00333   if (update_callback_)
00334     *callback = boost::bind(update_callback_, _1, error_state_changed);
00335 }
00336 
00337 // MUST hold state_lock_ when calling this!
00338 void InteractionHandler::updateStateJoint(robot_state::RobotState* state, const JointInteraction* vj,
00339                                           const geometry_msgs::Pose* feedback_pose, StateChangeCallbackFn* callback)
00340 {
00341   geometry_msgs::Pose rel_pose = *feedback_pose;
00342   if (!vj->parent_frame.empty() && !robot_state::Transforms::sameFrame(vj->parent_frame, planning_frame_))
00343   {
00344     Eigen::Affine3d p;
00345     tf::poseMsgToEigen(rel_pose, p);
00346     tf::poseEigenToMsg(state->getGlobalLinkTransform(vj->parent_frame).inverse() * p, rel_pose);
00347   }
00348 
00349   Eigen::Quaterniond q;
00350   tf::quaternionMsgToEigen(rel_pose.orientation, q);
00351   std::map<std::string, double> vals;
00352   if (vj->dof == 3)
00353   {
00354     vals[vj->joint_name + "/x"] = rel_pose.position.x;
00355     vals[vj->joint_name + "/y"] = rel_pose.position.y;
00356     Eigen::Vector3d xyz = q.matrix().eulerAngles(0, 1, 2);
00357     vals[vj->joint_name + "/theta"] = xyz[2];
00358   }
00359   else if (vj->dof == 6)
00360   {
00361     vals[vj->joint_name + "/trans_x"] = rel_pose.position.x;
00362     vals[vj->joint_name + "/trans_y"] = rel_pose.position.y;
00363     vals[vj->joint_name + "/trans_z"] = rel_pose.position.z;
00364     vals[vj->joint_name + "/rot_x"] = q.x();
00365     vals[vj->joint_name + "/rot_y"] = q.y();
00366     vals[vj->joint_name + "/rot_z"] = q.z();
00367     vals[vj->joint_name + "/rot_w"] = q.w();
00368   }
00369   state->setVariablePositions(vals);
00370   state->update();
00371 
00372   if (update_callback_)
00373     *callback = boost::bind(update_callback_, _1, false);
00374 }
00375 
00376 bool InteractionHandler::inError(const EndEffectorInteraction& eef) const
00377 {
00378   return getErrorState(eef.parent_group);
00379 }
00380 
00381 bool InteractionHandler::inError(const GenericInteraction& g) const
00382 {
00383   return getErrorState(g.marker_name_suffix);
00384 }
00385 
00386 bool InteractionHandler::inError(const JointInteraction& vj) const
00387 {
00388   return false;
00389 }
00390 
00391 void InteractionHandler::clearError(void)
00392 {
00393   boost::mutex::scoped_lock lock(state_lock_);
00394   error_state_.clear();
00395 }
00396 
00397 // return true if the state changed.
00398 // MUST hold state_lock_ when calling this!
00399 bool InteractionHandler::setErrorState(const std::string& name, bool new_error_state)
00400 {
00401   bool old_error_state = error_state_.find(name) != error_state_.end();
00402 
00403   if (new_error_state == old_error_state)
00404     return false;
00405 
00406   if (new_error_state)
00407     error_state_.insert(name);
00408   else
00409     error_state_.erase(name);
00410 
00411   return true;
00412 }
00413 
00414 bool InteractionHandler::getErrorState(const std::string& name) const
00415 {
00416   boost::mutex::scoped_lock lock(state_lock_);
00417   return error_state_.find(name) != error_state_.end();
00418 }
00419 
00420 bool InteractionHandler::transformFeedbackPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback,
00421                                                const geometry_msgs::Pose& offset, geometry_msgs::PoseStamped& tpose)
00422 {
00423   tpose.header = feedback->header;
00424   tpose.pose = feedback->pose;
00425   if (feedback->header.frame_id != planning_frame_)
00426   {
00427     if (tf_)
00428       try
00429       {
00430         tf::Stamped<tf::Pose> spose;
00431         tf::poseStampedMsgToTF(tpose, spose);
00432         // Express feedback (marker) pose in planning frame
00433         tf_->transformPose(planning_frame_, spose, spose);
00434         // Apply inverse of offset to bring feedback pose back into the end-effector support link frame
00435         tf::Transform tf_offset;
00436         tf::poseMsgToTF(offset, tf_offset);
00437         spose.setData(spose * tf_offset.inverse());
00438         tf::poseStampedTFToMsg(spose, tpose);
00439       }
00440       catch (tf::TransformException& e)
00441       {
00442         ROS_ERROR("Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
00443                   planning_frame_.c_str());
00444         return false;
00445       }
00446     else
00447     {
00448       ROS_ERROR("Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
00449                 tpose.header.frame_id.c_str(), planning_frame_.c_str());
00450       return false;
00451     }
00452   }
00453   return true;
00454 }
00455 
00456 // This syncs the InteractionHandler's KinematicOptionsMap with the
00457 // RobotInteraction's.  After this both will share the same
00458 // KinematicOptionsMap.
00459 //
00460 // With the constructors that take a RobotInteraction parameter this function
00461 // is not needed (except as a sanity check that the RobotInteraction and
00462 // InteractionHandler are matched).  This function is necessary because when
00463 // the old constructors are used the InteractionHandler may not know what
00464 // RobotInteraction it is associated with until after some options have been
00465 // set on the InteractionHandler.
00466 void InteractionHandler::setRobotInteraction(RobotInteraction* robot_interaction)
00467 {
00468   boost::mutex::scoped_lock lock(state_lock_);
00469 
00470   // Verivy that this InteractionHandler is only used with one
00471   // RobotInteraction.
00472   // This is the only use for robot_interaction_.
00473   if (robot_interaction_)
00474   {
00475     if (robot_interaction_ != robot_interaction)
00476     {
00477       ROS_ERROR("setKinematicOptions() called from 2 different RobotInteraction instances.");
00478     }
00479     return;
00480   }
00481 
00482   robot_interaction_ = robot_interaction;
00483 
00484   KinematicOptionsMapPtr shared_kinematic_options_map = robot_interaction->getKinematicOptionsMap();
00485 
00486   // merge old options into shared options
00487   // This is necessary because some legacy code sets values using deprecated
00488   // InteractionHandler methods before a RobotInteraction is associated with
00489   // this InteractionHandler.
00490   //
00491   // This is a nop if a constructor with a robot_interaction parameter is used.
00492   shared_kinematic_options_map->merge(*kinematic_options_map_);
00493 
00494   // from now on the InteractionHandler shares the same KinematicOptionsMap
00495   // with RobotInteraction.
00496   // The old *kinematic_options_map_ is automatically deleted by boost::shared_ptr.
00497   //
00498   // This is a nop if a constructor with a robot_interaction parameter is used.
00499   kinematic_options_map_ = shared_kinematic_options_map;
00500 }
00501 
00502 // ============= DEPRECATED FUNCTIONS =====================
00503 
00504 void InteractionHandler::setIKTimeout(double timeout)
00505 {
00506   KinematicOptions delta;
00507   delta.timeout_seconds_ = timeout;
00508 
00509   boost::mutex::scoped_lock lock(state_lock_);
00510   kinematic_options_map_->setOptions(KinematicOptionsMap::ALL, delta, KinematicOptions::TIMEOUT);
00511 }
00512 
00513 void InteractionHandler::setIKAttempts(unsigned int attempts)
00514 {
00515   KinematicOptions delta;
00516   delta.max_attempts_ = attempts;
00517 
00518   boost::mutex::scoped_lock lock(state_lock_);
00519   kinematic_options_map_->setOptions(KinematicOptionsMap::ALL, delta, KinematicOptions::MAX_ATTEMPTS);
00520 }
00521 
00522 void InteractionHandler::setKinematicsQueryOptions(const kinematics::KinematicsQueryOptions& opt)
00523 {
00524   KinematicOptions delta;
00525   delta.options_ = opt;
00526 
00527   boost::mutex::scoped_lock lock(state_lock_);
00528   kinematic_options_map_->setOptions(KinematicOptionsMap::ALL, delta, KinematicOptions::ALL_QUERY_OPTIONS);
00529 }
00530 
00531 void InteractionHandler::setKinematicsQueryOptionsForGroup(const std::string& group_name,
00532                                                            const kinematics::KinematicsQueryOptions& opt)
00533 {
00534   KinematicOptions delta;
00535   delta.options_ = opt;
00536 
00537   boost::mutex::scoped_lock lock(state_lock_);
00538   kinematic_options_map_->setOptions(group_name, delta, KinematicOptions::ALL_QUERY_OPTIONS);
00539 }
00540 
00541 void InteractionHandler::setGroupStateValidityCallback(const robot_state::GroupStateValidityCallbackFn& callback)
00542 {
00543   KinematicOptions delta;
00544   delta.state_validity_callback_ = callback;
00545 
00546   boost::mutex::scoped_lock lock(state_lock_);
00547   kinematic_options_map_->setOptions(KinematicOptionsMap::ALL, delta, KinematicOptions::STATE_VALIDITY_CALLBACK);
00548 }
00549 
00550 const kinematics::KinematicsQueryOptions& InteractionHandler::getKinematicsQueryOptions() const
00551 {
00552   boost::mutex::scoped_lock lock(state_lock_);
00553   return kinematic_options_map_->getOptions(KinematicOptionsMap::DEFAULT).options_;
00554 }
00555 
00556 void InteractionHandler::setUpdateCallback(const InteractionHandlerCallbackFn& callback)
00557 {
00558   boost::mutex::scoped_lock lock(state_lock_);
00559   update_callback_ = callback;
00560 }
00561 
00562 const InteractionHandlerCallbackFn& InteractionHandler::getUpdateCallback() const
00563 {
00564   boost::mutex::scoped_lock lock(state_lock_);
00565   return update_callback_;
00566 }
00567 
00568 void InteractionHandler::setMeshesVisible(bool visible)
00569 {
00570   boost::mutex::scoped_lock lock(state_lock_);
00571   display_meshes_ = visible;
00572 }
00573 
00574 bool InteractionHandler::getMeshesVisible() const
00575 {
00576   boost::mutex::scoped_lock lock(state_lock_);
00577   return display_meshes_;
00578 }
00579 
00580 void InteractionHandler::setControlsVisible(bool visible)
00581 {
00582   boost::mutex::scoped_lock lock(state_lock_);
00583   display_controls_ = visible;
00584 }
00585 
00586 bool InteractionHandler::getControlsVisible() const
00587 {
00588   boost::mutex::scoped_lock lock(state_lock_);
00589   return display_controls_;
00590 }
00591 }


robot_interaction
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:44