00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * Copyright (c) 2014, SRI International 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, Acorn Pooley */ 00037 00038 #ifndef MOVEIT_ROBOT_INTERACTION_LOCKED_ROBOT_STATE_ 00039 #define MOVEIT_ROBOT_INTERACTION_LOCKED_ROBOT_STATE_ 00040 00041 #include <moveit/macros/class_forward.h> 00042 #include <moveit/robot_state/robot_state.h> 00043 #include <boost/function.hpp> 00044 #include <boost/thread.hpp> 00045 00046 namespace robot_interaction 00047 { 00048 MOVEIT_CLASS_FORWARD(LockedRobotState); 00049 00051 // 00052 // Only allow one thread to modify the RobotState at a time. 00053 // 00054 // Allow any thread access to the RobotState when it is not being modified. If 00055 // a (const) reference to the robot state is held when the RobotState needs to 00056 // be modified, a copy is made and the copy is modified. Any externally held 00057 // references will be out of date but still valid. 00058 // 00059 // The RobotState can only be modified by passing a callback function which 00060 // does the modification. 00061 class LockedRobotState 00062 { 00063 public: 00064 LockedRobotState(const robot_state::RobotState& state); 00065 LockedRobotState(const robot_model::RobotModelPtr& model); 00066 00067 virtual ~LockedRobotState(); 00068 00070 // 00071 // This state may go stale, meaning the maintained state has been updated, 00072 // but it will never be modified while the caller is holding a reference to 00073 // it. 00074 // 00075 // The transforms in the returned state will always be up to date. 00076 robot_state::RobotStateConstPtr getState() const; 00077 00079 void setState(const robot_state::RobotState& state); 00080 00081 // This is a function that can modify the maintained state. 00082 typedef boost::function<void(robot_state::RobotState*)> ModifyStateFunction; 00083 00084 // Modify the state. 00085 // 00086 // This modifies the state by calling \e modify on it. 00087 // The \e modify function is passed a reference to the state which it can 00088 // modify. No threads will be given access to the state while the \e modify 00089 // function is running. 00090 void modifyState(const ModifyStateFunction& modify); 00091 00092 protected: 00093 // This is called when the internally maintained state has changed. 00094 // This is called with state_lock_ unlocked. 00095 // Default definition does nothing. Override to get notification of state 00096 // change. 00097 // TODO: is this needed? 00098 virtual void robotStateChanged(); 00099 00100 protected: 00101 // this locks all accesses to the state_ member. 00102 // The lock can also be used by subclasses to lock additional fields. 00103 mutable boost::mutex state_lock_; 00104 00105 private: 00106 // The state maintained by this class. 00107 // When a modify function is being called this is NULL. 00108 // PROTECTED BY state_lock_ 00109 robot_state::RobotStatePtr state_; 00110 }; 00111 } 00112 00113 #endif