00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Ioan Sucan */ 00036 00037 #ifndef MOVEIT_PLANNING_SCENE_MONITOR_CURRENT_STATE_MONITOR_ 00038 #define MOVEIT_PLANNING_SCENE_MONITOR_CURRENT_STATE_MONITOR_ 00039 00040 #include <ros/ros.h> 00041 #include <tf/tf.h> 00042 #include <moveit/robot_state/robot_state.h> 00043 #include <sensor_msgs/JointState.h> 00044 #include <boost/function.hpp> 00045 #include <boost/shared_ptr.hpp> 00046 #include <boost/thread/mutex.hpp> 00047 00048 namespace planning_scene_monitor 00049 { 00050 00051 typedef boost::function<void(const sensor_msgs::JointStateConstPtr &joint_state)> JointStateUpdateCallback; 00052 00055 class CurrentStateMonitor 00056 { 00057 public: 00058 00063 CurrentStateMonitor(const robot_model::RobotModelConstPtr &robot_model, const boost::shared_ptr<tf::Transformer> &tf); 00064 00065 ~CurrentStateMonitor(); 00066 00070 void startStateMonitor(const std::string &joint_states_topic = "joint_states"); 00071 00074 void stopStateMonitor(); 00075 00077 bool isActive() const; 00078 00080 const robot_model::RobotModelConstPtr& getRobotModel() const 00081 { 00082 return robot_model_; 00083 } 00084 00086 std::string getMonitoredTopic() const; 00087 00091 bool haveCompleteState() const; 00092 00097 bool haveCompleteState(const ros::Duration &age) const; 00098 00103 bool haveCompleteState(std::vector<std::string> &missing_joints) const; 00104 00110 bool haveCompleteState(const ros::Duration &age, std::vector<std::string> &missing_states) const; 00111 00114 robot_state::RobotStatePtr getCurrentState() const; 00115 00117 void setToCurrentState(robot_state::RobotState &upd) const; 00118 00120 ros::Time getCurrentStateTime() const; 00121 00124 std::pair<robot_state::RobotStatePtr, ros::Time> getCurrentStateAndTime() const; 00125 00128 std::map<std::string, double> getCurrentStateValues() const; 00129 00131 bool waitForCurrentState(double wait_time) const; 00132 00134 bool waitForCurrentState(const std::string &group, double wait_time) const; 00135 00137 const ros::Time& getMonitorStartTime() const 00138 { 00139 return monitor_start_time_; 00140 } 00141 00143 void addUpdateCallback(const JointStateUpdateCallback &fn); 00144 00146 void clearUpdateCallbacks(); 00147 00152 void setBoundsError(double error) 00153 { 00154 error_ = (error > 0) ? error : -error; 00155 } 00156 00161 double getBoundsError() const 00162 { 00163 return error_; 00164 } 00165 00166 private: 00167 00168 void jointStateCallback(const sensor_msgs::JointStateConstPtr &joint_state); 00169 bool isPassiveDOF(const std::string &dof) const; 00170 00171 ros::NodeHandle nh_; 00172 boost::shared_ptr<tf::Transformer> tf_; 00173 robot_model::RobotModelConstPtr robot_model_; 00174 robot_state::RobotState robot_state_; 00175 std::map<std::string, ros::Time> joint_time_; 00176 bool state_monitor_started_; 00177 ros::Time monitor_start_time_; 00178 double error_; 00179 ros::Subscriber joint_state_subscriber_; 00180 ros::Time current_state_time_; 00181 ros::Time last_tf_update_; 00182 00183 mutable boost::mutex state_update_lock_; 00184 std::vector< JointStateUpdateCallback > update_callbacks_; 00185 }; 00186 00187 MOVEIT_CLASS_FORWARD(CurrentStateMonitor); 00188 00189 } 00190 00191 #endif