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 typedef boost::function<void(const sensor_msgs::JointStateConstPtr& joint_state)> JointStateUpdateCallback; 00051 00054 class CurrentStateMonitor 00055 { 00056 public: 00062 CurrentStateMonitor(const robot_model::RobotModelConstPtr& robot_model, const boost::shared_ptr<tf::Transformer>& tf); 00063 00069 CurrentStateMonitor(const robot_model::RobotModelConstPtr& robot_model, const boost::shared_ptr<tf::Transformer>& tf, 00070 ros::NodeHandle nh); 00071 00072 ~CurrentStateMonitor(); 00073 00077 void startStateMonitor(const std::string& joint_states_topic = "joint_states"); 00078 00081 void stopStateMonitor(); 00082 00084 bool isActive() const; 00085 00087 const robot_model::RobotModelConstPtr& getRobotModel() const 00088 { 00089 return robot_model_; 00090 } 00091 00093 std::string getMonitoredTopic() const; 00094 00098 bool haveCompleteState() const; 00099 00104 bool haveCompleteState(const ros::Duration& age) const; 00105 00110 bool haveCompleteState(std::vector<std::string>& missing_joints) const; 00111 00117 bool haveCompleteState(const ros::Duration& age, std::vector<std::string>& missing_states) const; 00118 00121 robot_state::RobotStatePtr getCurrentState() const; 00122 00124 void setToCurrentState(robot_state::RobotState& upd) const; 00125 00127 ros::Time getCurrentStateTime() const; 00128 00131 std::pair<robot_state::RobotStatePtr, ros::Time> getCurrentStateAndTime() const; 00132 00135 std::map<std::string, double> getCurrentStateValues() const; 00136 00140 bool waitForCurrentState(const ros::Time t = ros::Time::now(), double wait_time = 1.0) const; 00141 00144 bool waitForCurrentState(double wait_time) const; 00145 00148 bool waitForCurrentState(const std::string& group, double wait_time) const; 00149 00151 const ros::Time& getMonitorStartTime() const 00152 { 00153 return monitor_start_time_; 00154 } 00155 00157 void addUpdateCallback(const JointStateUpdateCallback& fn); 00158 00160 void clearUpdateCallbacks(); 00161 00166 void setBoundsError(double error) 00167 { 00168 error_ = (error > 0) ? error : -error; 00169 } 00170 00175 double getBoundsError() const 00176 { 00177 return error_; 00178 } 00179 00180 private: 00181 void jointStateCallback(const sensor_msgs::JointStateConstPtr& joint_state); 00182 bool isPassiveOrMimicDOF(const std::string& dof) const; 00183 00184 ros::NodeHandle nh_; 00185 boost::shared_ptr<tf::Transformer> tf_; 00186 robot_model::RobotModelConstPtr robot_model_; 00187 robot_state::RobotState robot_state_; 00188 std::map<std::string, ros::Time> joint_time_; 00189 bool state_monitor_started_; 00190 ros::Time monitor_start_time_; 00191 double error_; 00192 ros::Subscriber joint_state_subscriber_; 00193 ros::Time current_state_time_; 00194 ros::Time last_tf_update_; 00195 00196 mutable boost::mutex state_update_lock_; 00197 std::vector<JointStateUpdateCallback> update_callbacks_; 00198 }; 00199 00200 MOVEIT_CLASS_FORWARD(CurrentStateMonitor); 00201 } 00202 00203 #endif