00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/planning_scene_monitor/current_state_monitor.h>
00038 #include <tf_conversions/tf_eigen.h>
00039 #include <limits>
00040
00041 planning_scene_monitor::CurrentStateMonitor::CurrentStateMonitor(const robot_model::RobotModelConstPtr& robot_model,
00042 const boost::shared_ptr<tf::Transformer>& tf)
00043 : CurrentStateMonitor(robot_model, tf, ros::NodeHandle())
00044 {
00045 }
00046
00047 planning_scene_monitor::CurrentStateMonitor::CurrentStateMonitor(const robot_model::RobotModelConstPtr& robot_model,
00048 const boost::shared_ptr<tf::Transformer>& tf,
00049 ros::NodeHandle nh)
00050 : nh_(nh)
00051 , tf_(tf)
00052 , robot_model_(robot_model)
00053 , robot_state_(robot_model)
00054 , state_monitor_started_(false)
00055 , copy_dynamics_(false)
00056 , error_(std::numeric_limits<double>::epsilon())
00057 {
00058 robot_state_.setToDefaultValues();
00059 }
00060
00061 planning_scene_monitor::CurrentStateMonitor::~CurrentStateMonitor()
00062 {
00063 stopStateMonitor();
00064 }
00065
00066 robot_state::RobotStatePtr planning_scene_monitor::CurrentStateMonitor::getCurrentState() const
00067 {
00068 boost::mutex::scoped_lock slock(state_update_lock_);
00069 robot_state::RobotState* result = new robot_state::RobotState(robot_state_);
00070 return robot_state::RobotStatePtr(result);
00071 }
00072
00073 ros::Time planning_scene_monitor::CurrentStateMonitor::getCurrentStateTime() const
00074 {
00075 boost::mutex::scoped_lock slock(state_update_lock_);
00076 return current_state_time_;
00077 }
00078
00079 std::pair<robot_state::RobotStatePtr, ros::Time>
00080 planning_scene_monitor::CurrentStateMonitor::getCurrentStateAndTime() const
00081 {
00082 boost::mutex::scoped_lock slock(state_update_lock_);
00083 robot_state::RobotState* result = new robot_state::RobotState(robot_state_);
00084 return std::make_pair(robot_state::RobotStatePtr(result), current_state_time_);
00085 }
00086
00087 std::map<std::string, double> planning_scene_monitor::CurrentStateMonitor::getCurrentStateValues() const
00088 {
00089 std::map<std::string, double> m;
00090 boost::mutex::scoped_lock slock(state_update_lock_);
00091 const double* pos = robot_state_.getVariablePositions();
00092 const std::vector<std::string>& names = robot_state_.getVariableNames();
00093 for (std::size_t i = 0; i < names.size(); ++i)
00094 m[names[i]] = pos[i];
00095 return m;
00096 }
00097
00098 void planning_scene_monitor::CurrentStateMonitor::setToCurrentState(robot_state::RobotState& upd) const
00099 {
00100 boost::mutex::scoped_lock slock(state_update_lock_);
00101 const double* pos = robot_state_.getVariablePositions();
00102 upd.setVariablePositions(pos);
00103 }
00104
00105 void planning_scene_monitor::CurrentStateMonitor::addUpdateCallback(const JointStateUpdateCallback& fn)
00106 {
00107 if (fn)
00108 update_callbacks_.push_back(fn);
00109 }
00110
00111 void planning_scene_monitor::CurrentStateMonitor::clearUpdateCallbacks()
00112 {
00113 update_callbacks_.clear();
00114 }
00115
00116 void planning_scene_monitor::CurrentStateMonitor::startStateMonitor(const std::string& joint_states_topic)
00117 {
00118 if (!state_monitor_started_ && robot_model_)
00119 {
00120 joint_time_.clear();
00121 if (joint_states_topic.empty())
00122 ROS_ERROR("The joint states topic cannot be an empty string");
00123 else
00124 joint_state_subscriber_ = nh_.subscribe(joint_states_topic, 25, &CurrentStateMonitor::jointStateCallback, this);
00125 state_monitor_started_ = true;
00126 monitor_start_time_ = ros::Time::now();
00127 ROS_DEBUG("Listening to joint states on topic '%s'", nh_.resolveName(joint_states_topic).c_str());
00128 }
00129 }
00130
00131 bool planning_scene_monitor::CurrentStateMonitor::isActive() const
00132 {
00133 return state_monitor_started_;
00134 }
00135
00136 void planning_scene_monitor::CurrentStateMonitor::stopStateMonitor()
00137 {
00138 if (state_monitor_started_)
00139 {
00140 joint_state_subscriber_.shutdown();
00141 ROS_DEBUG("No longer listening o joint states");
00142 state_monitor_started_ = false;
00143 }
00144 }
00145
00146 std::string planning_scene_monitor::CurrentStateMonitor::getMonitoredTopic() const
00147 {
00148 if (joint_state_subscriber_)
00149 return joint_state_subscriber_.getTopic();
00150 else
00151 return "";
00152 }
00153
00154 bool planning_scene_monitor::CurrentStateMonitor::isPassiveOrMimicDOF(const std::string& dof) const
00155 {
00156 if (robot_model_->hasJointModel(dof))
00157 {
00158 if (robot_model_->getJointModel(dof)->isPassive() || robot_model_->getJointModel(dof)->getMimic())
00159 return true;
00160 }
00161 else
00162 {
00163
00164 std::size_t slash = dof.find_last_of("/");
00165 if (slash != std::string::npos)
00166 {
00167 std::string joint_name = dof.substr(0, slash);
00168 if (robot_model_->hasJointModel(joint_name))
00169 if (robot_model_->getJointModel(joint_name)->isPassive() || robot_model_->getJointModel(joint_name)->getMimic())
00170 return true;
00171 }
00172 }
00173 return false;
00174 }
00175
00176 bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState() const
00177 {
00178 bool result = true;
00179 const std::vector<std::string>& dof = robot_model_->getVariableNames();
00180 boost::mutex::scoped_lock slock(state_update_lock_);
00181 for (std::size_t i = 0; i < dof.size(); ++i)
00182 if (joint_time_.find(dof[i]) == joint_time_.end())
00183 {
00184 if (!isPassiveOrMimicDOF(dof[i]))
00185 {
00186 ROS_DEBUG("Joint variable '%s' has never been updated", dof[i].c_str());
00187 result = false;
00188 }
00189 }
00190 return result;
00191 }
00192
00193 bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState(std::vector<std::string>& missing_states) const
00194 {
00195 bool result = true;
00196 const std::vector<std::string>& dof = robot_model_->getVariableNames();
00197 boost::mutex::scoped_lock slock(state_update_lock_);
00198 for (std::size_t i = 0; i < dof.size(); ++i)
00199 if (joint_time_.find(dof[i]) == joint_time_.end())
00200 if (!isPassiveOrMimicDOF(dof[i]))
00201 {
00202 missing_states.push_back(dof[i]);
00203 result = false;
00204 }
00205 return result;
00206 }
00207
00208 bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState(const ros::Duration& age) const
00209 {
00210 bool result = true;
00211 const std::vector<std::string>& dof = robot_model_->getVariableNames();
00212 ros::Time now = ros::Time::now();
00213 ros::Time old = now - age;
00214 boost::mutex::scoped_lock slock(state_update_lock_);
00215 for (std::size_t i = 0; i < dof.size(); ++i)
00216 {
00217 if (isPassiveOrMimicDOF(dof[i]))
00218 continue;
00219 std::map<std::string, ros::Time>::const_iterator it = joint_time_.find(dof[i]);
00220 if (it == joint_time_.end())
00221 {
00222 ROS_DEBUG("Joint variable '%s' has never been updated", dof[i].c_str());
00223 result = false;
00224 }
00225 else if (it->second < old)
00226 {
00227 ROS_DEBUG("Joint variable '%s' was last updated %0.3lf seconds ago (older than the allowed %0.3lf seconds)",
00228 dof[i].c_str(), (now - it->second).toSec(), age.toSec());
00229 result = false;
00230 }
00231 }
00232 return result;
00233 }
00234
00235 bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState(const ros::Duration& age,
00236 std::vector<std::string>& missing_states) const
00237 {
00238 bool result = true;
00239 const std::vector<std::string>& dof = robot_model_->getVariableNames();
00240 ros::Time now = ros::Time::now();
00241 ros::Time old = now - age;
00242 boost::mutex::scoped_lock slock(state_update_lock_);
00243 for (std::size_t i = 0; i < dof.size(); ++i)
00244 {
00245 if (isPassiveOrMimicDOF(dof[i]))
00246 continue;
00247 std::map<std::string, ros::Time>::const_iterator it = joint_time_.find(dof[i]);
00248 if (it == joint_time_.end())
00249 {
00250 ROS_DEBUG("Joint variable '%s' has never been updated", dof[i].c_str());
00251 missing_states.push_back(dof[i]);
00252 result = false;
00253 }
00254 else if (it->second < old)
00255 {
00256 ROS_DEBUG("Joint variable '%s' was last updated %0.3lf seconds ago (older than the allowed %0.3lf seconds)",
00257 dof[i].c_str(), (now - it->second).toSec(), age.toSec());
00258 missing_states.push_back(dof[i]);
00259 result = false;
00260 }
00261 }
00262 return result;
00263 }
00264
00265 bool planning_scene_monitor::CurrentStateMonitor::waitForCurrentState(double wait_time) const
00266 {
00267 double slept_time = 0.0;
00268 double sleep_step_s = std::min(0.05, wait_time / 10.0);
00269 ros::Duration sleep_step(sleep_step_s);
00270 while (!haveCompleteState() && slept_time < wait_time)
00271 {
00272 sleep_step.sleep();
00273 slept_time += sleep_step_s;
00274 }
00275 return haveCompleteState();
00276 }
00277
00278 bool planning_scene_monitor::CurrentStateMonitor::waitForCurrentState(const std::string& group, double wait_time) const
00279 {
00280 if (waitForCurrentState(wait_time))
00281 return true;
00282 bool ok = true;
00283
00284
00285 std::vector<std::string> missing_joints;
00286 if (!haveCompleteState(missing_joints))
00287 {
00288 const robot_model::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
00289 if (jmg)
00290 {
00291 std::set<std::string> mj;
00292 mj.insert(missing_joints.begin(), missing_joints.end());
00293 const std::vector<std::string>& names = jmg->getJointModelNames();
00294 bool ok = true;
00295 for (std::size_t i = 0; ok && i < names.size(); ++i)
00296 if (mj.find(names[i]) != mj.end())
00297 ok = false;
00298 }
00299 else
00300 ok = false;
00301 }
00302 return ok;
00303 }
00304
00305 void planning_scene_monitor::CurrentStateMonitor::jointStateCallback(const sensor_msgs::JointStateConstPtr& joint_state)
00306 {
00307 if (joint_state->name.size() != joint_state->position.size())
00308 {
00309 ROS_ERROR_THROTTLE(1, "State monitor received invalid joint state (number of joint names does not match number of "
00310 "positions)");
00311 return;
00312 }
00313 bool update = false;
00314
00315 {
00316 boost::mutex::scoped_lock _(state_update_lock_);
00317
00318 std::size_t n = joint_state->name.size();
00319 current_state_time_ = joint_state->header.stamp;
00320 for (std::size_t i = 0; i < n; ++i)
00321 {
00322 const robot_model::JointModel* jm = robot_model_->getJointModel(joint_state->name[i]);
00323 if (!jm)
00324 continue;
00325
00326 if (jm->getVariableCount() != 1)
00327 continue;
00328
00329 joint_time_[joint_state->name[i]] = joint_state->header.stamp;
00330
00331 if (robot_state_.getJointPositions(jm)[0] != joint_state->position[i])
00332 {
00333 update = true;
00334 robot_state_.setJointPositions(jm, &(joint_state->position[i]));
00335
00336
00337 if (copy_dynamics_)
00338 {
00339
00340 if (joint_state->name.size() == joint_state->velocity.size())
00341 {
00342 robot_state_.setJointVelocities(jm, &(joint_state->velocity[i]));
00343
00344
00345 if (joint_state->name.size() == joint_state->effort.size())
00346 {
00347 robot_state_.setJointEfforts(jm, &(joint_state->effort[i]));
00348 }
00349 }
00350 }
00351
00352
00353 if (jm->getType() == robot_model::JointModel::REVOLUTE)
00354 if (static_cast<const robot_model::RevoluteJointModel*>(jm)->isContinuous())
00355 continue;
00356
00357 const robot_model::VariableBounds& b =
00358 jm->getVariableBounds()[0];
00359
00360
00361
00362 if (joint_state->position[i] < b.min_position_ && joint_state->position[i] >= b.min_position_ - error_)
00363 robot_state_.setJointPositions(jm, &b.min_position_);
00364 else if (joint_state->position[i] > b.max_position_ && joint_state->position[i] <= b.max_position_ + error_)
00365 robot_state_.setJointPositions(jm, &b.max_position_);
00366 }
00367 }
00368
00369
00370 if (tf_ && (robot_model_->getRootJoint()->getType() == robot_model::JointModel::PLANAR ||
00371 robot_model_->getRootJoint()->getType() == robot_model::JointModel::FLOATING))
00372 {
00373 const std::string& child_frame = robot_model_->getRootLink()->getName();
00374 const std::string& parent_frame = robot_model_->getModelFrame();
00375
00376 std::string err;
00377 ros::Time tm;
00378 tf::StampedTransform transf;
00379 bool ok = false;
00380 if (tf_->getLatestCommonTime(parent_frame, child_frame, tm, &err) == tf::NO_ERROR)
00381 {
00382 try
00383 {
00384 tf_->lookupTransform(parent_frame, child_frame, tm, transf);
00385 ok = true;
00386 }
00387 catch (tf::TransformException& ex)
00388 {
00389 ROS_ERROR_THROTTLE(1, "Unable to lookup transform from %s to %s. Exception: %s", parent_frame.c_str(),
00390 child_frame.c_str(), ex.what());
00391 }
00392 }
00393 else
00394 ROS_DEBUG_THROTTLE(1, "Unable to lookup transform from %s to %s: no common time.", parent_frame.c_str(),
00395 child_frame.c_str());
00396 if (ok && last_tf_update_ != tm)
00397 {
00398 update = true;
00399 last_tf_update_ = tm;
00400 const std::vector<std::string>& vars = robot_model_->getRootJoint()->getVariableNames();
00401 for (std::size_t j = 0; j < vars.size(); ++j)
00402 joint_time_[vars[j]] = tm;
00403 Eigen::Affine3d eigen_transf;
00404 tf::transformTFToEigen(transf, eigen_transf);
00405 robot_state_.setJointPositions(robot_model_->getRootJoint(), eigen_transf);
00406 }
00407 }
00408 }
00409
00410
00411 if (update)
00412 for (std::size_t i = 0; i < update_callbacks_.size(); ++i)
00413 update_callbacks_[i](joint_state);
00414 }