$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, 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 the 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 00037 #ifndef PLANNING_ENVIRONMENT_MONITORS_KINEMATIC_MODEL_STATE_MONITOR_ 00038 #define PLANNING_ENVIRONMENT_MONITORS_KINEMATIC_MODEL_STATE_MONITOR_ 00039 00040 #include "planning_environment/models/robot_models.h" 00041 #include <tf/transform_datatypes.h> 00042 #include <tf/transform_listener.h> 00043 #include <tf/message_filter.h> 00044 #include <message_filters/subscriber.h> 00045 #include <sensor_msgs/JointState.h> 00046 #include <arm_navigation_msgs/RobotState.h> 00047 #include <boost/bind.hpp> 00048 #include <vector> 00049 #include <string> 00050 #include <map> 00051 #include <planning_models/kinematic_state.h> 00052 00053 namespace planning_environment 00054 { 00055 00060 class KinematicModelStateMonitor 00061 { 00062 public: 00063 00064 KinematicModelStateMonitor(RobotModels *rm, tf::TransformListener *tf) : nh_("~") 00065 { 00066 rm_ = rm; 00067 tf_ = tf; 00068 setupRSM(); 00069 } 00070 00071 virtual ~KinematicModelStateMonitor(void) 00072 { 00073 } 00074 00076 void startStateMonitor(void); 00077 00079 void stopStateMonitor(void); 00080 00082 bool isStateMonitorStarted(void) const 00083 { 00084 return state_monitor_started_; 00085 } 00086 00087 void addOnStateUpdateCallback(const boost::function<void(const sensor_msgs::JointStateConstPtr &joint_state)> &callback) { 00088 on_state_update_callback_ = callback; 00089 } 00090 00092 const planning_models::KinematicModel* getKinematicModel(void) const 00093 { 00094 return kmodel_; 00095 } 00096 00098 RobotModels* getRobotModels(void) const 00099 { 00100 return rm_; 00101 } 00102 00104 tf::TransformListener *getTransformListener(void) const 00105 { 00106 return tf_; 00107 } 00108 00110 bool haveState(void) const 00111 { 00112 return have_joint_state_ && have_pose_; 00113 } 00114 00116 const ros::Time& lastJointStateUpdate(void) const 00117 { 00118 return last_joint_state_update_; 00119 } 00120 00122 const ros::Time& lastPoseUpdate(void) const 00123 { 00124 return last_pose_update_; 00125 } 00126 00128 void waitForState(void) const; 00129 00131 bool isJointStateUpdated(double sec) const; 00132 00136 bool isPoseUpdated(double sec) const; 00137 00139 void printRobotState(void) const; 00140 00142 void setStateValuesFromCurrentValues(planning_models::KinematicState& state) const; 00143 00144 bool getCurrentRobotState(arm_navigation_msgs::RobotState &robot_state) const; 00145 00146 bool setKinematicStateToTime(const ros::Time& time, 00147 planning_models::KinematicState& state) const; 00148 00149 bool getCachedJointStateValues(const ros::Time& time, std::map<std::string, double>& ret_map) const; 00150 00151 bool allJointsUpdated(ros::Duration dur = ros::Duration()) const; 00152 00153 //need to pass by value for thread safety 00154 std::map<std::string, double> getCurrentJointStateValues() const { 00155 current_joint_values_lock_.lock(); 00156 std::map<std::string, double> ret_values = current_joint_state_map_; 00157 current_joint_values_lock_.unlock(); 00158 return ret_values; 00159 } 00160 00161 protected: 00162 00163 void setupRSM(void); 00164 void jointStateCallback(const sensor_msgs::JointStateConstPtr &joint_state); 00165 00166 std::list<std::pair<ros::Time, std::map<std::string, double> > >joint_state_map_cache_; 00167 00168 std::map<std::string, ros::Time> last_joint_update_; 00169 std::map<std::string, double> current_joint_state_map_; 00170 00171 mutable boost::recursive_mutex current_joint_values_lock_; 00172 00173 double joint_state_cache_time_; 00174 double joint_state_cache_allowed_difference_; 00175 00176 RobotModels *rm_; 00177 00178 const planning_models::KinematicModel* kmodel_; 00179 00180 bool state_monitor_started_; 00181 bool printed_out_of_date_; 00182 00183 ros::NodeHandle nh_; 00184 ros::NodeHandle root_handle_; 00185 ros::Subscriber joint_state_subscriber_; 00186 tf::TransformListener *tf_; 00187 00188 tf::Pose pose_; 00189 std::string robot_frame_; 00190 00191 boost::function<void(const sensor_msgs::JointStateConstPtr &joint_state)> on_state_update_callback_; 00192 00193 bool have_pose_; 00194 bool have_joint_state_; 00195 ros::Time last_joint_state_update_; 00196 ros::Time last_pose_update_; 00197 }; 00198 00199 } 00200 00201 #endif