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
00037 #include "planning_environment/monitors/kinematic_model_state_monitor.h"
00038 #include "planning_environment/util/construct_object.h"
00039 #include <angles/angles.h>
00040 #include <sstream>
00041
00042 void planning_environment::KinematicModelStateMonitor::setupRSM(void)
00043 {
00044 stateMonitorStarted_ = false;
00045 onStateUpdate_ = NULL;
00046 havePose_ = haveJointState_ = false;
00047 robotVelocity_ = 0.0;
00048
00049 printed_out_of_date_ = false;
00050 if (rm_->loadedModels())
00051 {
00052 kmodel_ = rm_->getKinematicModel();
00053 robot_frame_ = kmodel_->getRoot()->getChildLinkModel()->getName();
00054 ROS_INFO("Robot frame is '%s'", robot_frame_.c_str());
00055 startStateMonitor();
00056 } else {
00057 ROS_INFO("Can't start state monitor yet");
00058 }
00059
00060 nh_.param<double>("joint_state_cache_time", joint_state_cache_time_, 2.0);
00061 nh_.param<double>("joint_state_cache_allowed_difference", joint_state_cache_allowed_difference_, .25);
00062
00063 }
00064
00065 void planning_environment::KinematicModelStateMonitor::startStateMonitor(void)
00066 {
00067 if (stateMonitorStarted_)
00068 return;
00069
00070 if (rm_->loadedModels())
00071 {
00072 jointStateSubscriber_ = root_handle_.subscribe("joint_states", 25, &KinematicModelStateMonitor::jointStateCallback, this);
00073 ROS_DEBUG("Listening to joint states");
00074
00075 }
00076 stateMonitorStarted_ = true;
00077 }
00078
00079 void planning_environment::KinematicModelStateMonitor::stopStateMonitor(void)
00080 {
00081 if (!stateMonitorStarted_)
00082 return;
00083
00084 jointStateSubscriber_.shutdown();
00085
00086 joint_state_map_cache_.clear();
00087
00088 ROS_DEBUG("Kinematic state is no longer being monitored");
00089
00090 stateMonitorStarted_ = false;
00091 }
00092
00093 void planning_environment::KinematicModelStateMonitor::jointStateCallback(const sensor_msgs::JointStateConstPtr &jointState)
00094 {
00095
00096
00097 planning_models::KinematicState state(kmodel_);
00098
00099 current_joint_values_lock_.lock();
00100
00101 state.setKinematicState(current_joint_state_map_);
00102
00103 static bool first_time = true;
00104
00105 unsigned int n = jointState->name.size();
00106 if (jointState->name.size() != jointState->position.size() || jointState->name.size() !=jointState->velocity.size())
00107 {
00108 ROS_ERROR("Planning environment received invalid joint state");
00109 current_joint_values_lock_.unlock();
00110 return;
00111 }
00112
00113 robotVelocity_ = 0.0;
00114 std::map<std::string, double> joint_state_map;
00115 for (unsigned int i = 0 ; i < n ; ++i)
00116 {
00117 joint_state_map[jointState->name[i]] = jointState->position[i];
00118 robotVelocity_ += jointState->velocity[i];
00119 }
00120
00121 std::vector<planning_models::KinematicState::JointState*>& joint_state_vector = state.getJointStateVector();
00122
00123 for(std::vector<planning_models::KinematicState::JointState*>::iterator it = joint_state_vector.begin();
00124 it != joint_state_vector.end();
00125 it++) {
00126 bool tfSets = false;
00127 bool jointStateSets = false;
00128
00129 std::string parent_frame_id = (*it)->getParentFrameId();
00130 std::string child_frame_id = (*it)->getChildFrameId();
00131 if(!parent_frame_id.empty() && !child_frame_id.empty()) {
00132 std::string err;
00133 ros::Time tm;
00134 tf::StampedTransform transf;
00135 bool ok = false;
00136 if (tf_->getLatestCommonTime(parent_frame_id, child_frame_id, tm, &err) == tf::NO_ERROR) {
00137 ok = true;
00138 try
00139 {
00140 tf_->lookupTransform(parent_frame_id, child_frame_id, tm, transf);
00141 }
00142 catch(tf::TransformException& ex)
00143 {
00144 ROS_ERROR("Unable to lookup transform from %s to %s. Exception: %s", parent_frame_id.c_str(), child_frame_id.c_str(), ex.what());
00145 ok = false;
00146 }
00147 } else {
00148 ROS_DEBUG("Unable to lookup transform from %s to %s: no common time.", parent_frame_id.c_str(), child_frame_id.c_str());
00149 ok = false;
00150 }
00151 if(ok) {
00152 tfSets = (*it)->setJointStateValues(transf);
00153 if(tfSets) {
00154 const std::vector<std::string>& joint_state_names = (*it)->getJointStateNameOrder();
00155 for(std::vector<std::string>::const_iterator it = joint_state_names.begin();
00156 it != joint_state_names.end();
00157 it++) {
00158 last_joint_update_[*it] = tm;
00159 }
00160 }
00161
00162
00163
00164
00165 havePose_ = tfSets;
00166 lastPoseUpdate_ = tm;
00167 }
00168 }
00169
00170 jointStateSets = (*it)->setJointStateValues(joint_state_map);
00171 if(jointStateSets) {
00172 const std::vector<std::string>& joint_state_names = (*it)->getJointStateNameOrder();
00173 for(std::vector<std::string>::const_iterator it = joint_state_names.begin();
00174 it != joint_state_names.end();
00175 it++) {
00176 last_joint_update_[*it] = jointState->header.stamp;
00177 }
00178 }
00179 }
00180
00181 state.updateKinematicLinks();
00182 state.getKinematicStateValues(current_joint_state_map_);
00183
00184 if(allJointsUpdated()) {
00185 haveJointState_ = true;
00186 lastJointStateUpdate_ = jointState->header.stamp;
00187
00188 if(!joint_state_map_cache_.empty()) {
00189 if(jointState->header.stamp-joint_state_map_cache_.back().first > ros::Duration(joint_state_cache_allowed_difference_)) {
00190 ROS_DEBUG_STREAM("Introducing joint state cache sparsity time of " << (jointState->header.stamp-joint_state_map_cache_.back().first).toSec());
00191 }
00192 }
00193
00194 joint_state_map_cache_.push_back(std::pair<ros::Time, std::map<std::string, double> >(jointState->header.stamp,
00195 current_joint_state_map_));
00196 }
00197
00198 if(haveJointState_) {
00199 while(1) {
00200 if(joint_state_map_cache_.empty()) {
00201 ROS_WARN("Empty joint state map cache");
00202 break;
00203 }
00204 if((ros::Time::now()-joint_state_map_cache_.front().first) > ros::Duration(joint_state_cache_time_)) {
00205 joint_state_map_cache_.pop_front();
00206 } else {
00207 break;
00208 }
00209 }
00210 }
00211 robotVelocity_ = sqrt(robotVelocity_);
00212
00213 first_time = false;
00214
00215 if(!allJointsUpdated(ros::Duration(1.0))) {
00216 if(!printed_out_of_date_) {
00217 ROS_WARN_STREAM("Got joint state update but did not update some joints for more than 1 second. Turn on DEBUG for more info");
00218 printed_out_of_date_ = true;
00219 }
00220 } else {
00221 printed_out_of_date_ = false;
00222 }
00223 if(onStateUpdate_ != NULL) {
00224 onStateUpdate_();
00225 }
00226 current_joint_values_lock_.unlock();
00227 }
00228
00229 bool planning_environment::KinematicModelStateMonitor::allJointsUpdated(ros::Duration allowed_dur) const {
00230 current_joint_values_lock_.lock();
00231 bool ret = true;
00232 for(std::map<std::string, double>::const_iterator it = current_joint_state_map_.begin();
00233 it != current_joint_state_map_.end();
00234 it++) {
00235 if(last_joint_update_.find(it->first) == last_joint_update_.end()) {
00236 ROS_DEBUG_STREAM("Joint " << it->first << " not yet updated");
00237 ret = false;
00238 continue;
00239 }
00240 if(allowed_dur != ros::Duration()) {
00241 ros::Duration dur = ros::Time::now()-last_joint_update_.find(it->first)->second;
00242 if(dur > allowed_dur) {
00243 ROS_DEBUG_STREAM("Joint " << it->first << " last updated " << dur.toSec() << " where allowed duration is " << allowed_dur.toSec());
00244 ret = false;
00245 continue;
00246 }
00247 }
00248 }
00249 current_joint_values_lock_.unlock();
00250 return ret;
00251 }
00252
00253 void planning_environment::KinematicModelStateMonitor::setStateValuesFromCurrentValues(planning_models::KinematicState& state) const
00254 {
00255 current_joint_values_lock_.lock();
00256 state.setKinematicState(current_joint_state_map_);
00257 current_joint_values_lock_.unlock();
00258 }
00259
00260 void planning_environment::KinematicModelStateMonitor::setRobotStateAndComputeTransforms(const motion_planning_msgs::RobotState &robot_state,
00261 planning_models::KinematicState& state) const
00262 {
00263 setStateValuesFromCurrentValues(state);
00264 std::map<std::string, double> joint_state_map;
00265 for (unsigned int i = 0 ; i < robot_state.joint_state.name.size(); ++i)
00266 {
00267 joint_state_map[robot_state.joint_state.name[i]] = robot_state.joint_state.position[i];
00268 }
00269
00270
00271 for(unsigned int i = 0; i < robot_state.multi_dof_joint_state.joint_names.size(); i++) {
00272 std::string joint_name = robot_state.multi_dof_joint_state.joint_names[i];
00273 if(!state.hasJointState(joint_name)) {
00274 ROS_WARN_STREAM("No joint matching multi-dof joint " << joint_name);
00275 continue;
00276 }
00277 planning_models::KinematicState::JointState* joint_state = state.getJointState(joint_name);
00278 if(robot_state.multi_dof_joint_state.frame_ids[i] != joint_state->getParentFrameId() ||
00279 robot_state.multi_dof_joint_state.child_frame_ids[i] != joint_state->getChildFrameId()) {
00280 ROS_WARN_STREAM("Robot state msg has bad multi_dof transform");
00281 } else {
00282 tf::StampedTransform transf;
00283 tf::poseMsgToTF(robot_state.multi_dof_joint_state.poses[i], transf);
00284 joint_state->setJointStateValues(transf);
00285 }
00286 }
00287 state.setKinematicState(joint_state_map);
00288 }
00289
00290 bool planning_environment::KinematicModelStateMonitor::getCurrentRobotState(motion_planning_msgs::RobotState& robot_state) const
00291 {
00292 planning_models::KinematicState state(kmodel_);
00293 setStateValuesFromCurrentValues(state);
00294 return(convertKinematicStateToRobotState(state,robot_state));
00295 }
00296
00297 bool planning_environment::KinematicModelStateMonitor::setKinematicStateToTime(const ros::Time& time,
00298 planning_models::KinematicState& state) const
00299 {
00300 std::map<std::string, double> joint_value_map;
00301 if(!getCachedJointStateValues(time, joint_value_map)) {
00302 return false;
00303 }
00304 state.setKinematicState(joint_value_map);
00305 return true;
00306 }
00307
00308 bool planning_environment::KinematicModelStateMonitor::convertKinematicStateToRobotState(const planning_models::KinematicState& kinematic_state,
00309 motion_planning_msgs::RobotState &robot_state) const
00310 {
00311 robot_state.joint_state.position.clear();
00312 robot_state.joint_state.name.clear();
00313
00314 const std::vector<planning_models::KinematicState::JointState*> joints = kinematic_state.getJointStateVector();
00315 for(std::vector<planning_models::KinematicState::JointState*>::const_iterator it = joints.begin();
00316 it != joints.end();
00317 it++) {
00318 const std::vector<double>& joint_state_values = (*it)->getJointStateValues();
00319 const std::vector<std::string>& joint_state_value_names = (*it)->getJointStateNameOrder();
00320 for(unsigned int i = 0; i < joint_state_values.size(); i++) {
00321 robot_state.joint_state.name.push_back(joint_state_value_names[i]);
00322 robot_state.joint_state.position.push_back(joint_state_values[i]);
00323 }
00324 if(!(*it)->getParentFrameId().empty() && !(*it)->getChildFrameId().empty()) {
00325 robot_state.multi_dof_joint_state.stamp = lastPoseUpdate();
00326 robot_state.multi_dof_joint_state.joint_names.push_back((*it)->getName());
00327 robot_state.multi_dof_joint_state.frame_ids.push_back((*it)->getParentFrameId());
00328 robot_state.multi_dof_joint_state.child_frame_ids.push_back((*it)->getChildFrameId());
00329 tf::Pose p((*it)->getVariableTransform());
00330 geometry_msgs::Pose pose;
00331 tf::poseTFToMsg(p, pose);
00332 robot_state.multi_dof_joint_state.poses.push_back(pose);
00333 }
00334 }
00335 robot_state.joint_state.header.stamp = lastJointStateUpdate();
00336 robot_state.joint_state.header.frame_id = getWorldFrameId();
00337 return true;
00338 }
00339
00340 bool planning_environment::KinematicModelStateMonitor::getCachedJointStateValues(const ros::Time& time, std::map<std::string, double>& ret_map) const {
00341
00342 current_joint_values_lock_.lock();
00343
00344
00345 if(time-ros::Duration(joint_state_cache_allowed_difference_) > joint_state_map_cache_.back().first) {
00346 ROS_WARN("Asking for time substantially newer than that contained in cache");
00347 current_joint_values_lock_.unlock();
00348 return false;
00349 }
00350 if(time+ros::Duration(joint_state_cache_allowed_difference_) < joint_state_map_cache_.front().first) {
00351 ROS_WARN_STREAM("Asking for time substantially older than that contained in cache " << time.toSec() << " " << joint_state_map_cache_.front().first.toSec());
00352 current_joint_values_lock_.unlock();
00353 return false;
00354 }
00355
00356
00357 if(time < joint_state_map_cache_.front().first) {
00358 ret_map = joint_state_map_cache_.front().second;
00359 } else if (time > joint_state_map_cache_.back().first) {
00360 ret_map = joint_state_map_cache_.back().second;
00361 } else {
00362 std::list<std::pair<ros::Time, std::map<std::string, double> > >::const_reverse_iterator next = ++joint_state_map_cache_.rbegin();
00363 std::list<std::pair<ros::Time, std::map<std::string, double> > >::const_reverse_iterator cur = joint_state_map_cache_.rbegin();
00364 while(next != joint_state_map_cache_.rbegin()) {
00365 if(time < cur->first && time > next->first) {
00366 ros::Duration ear_diff = time - next->first;
00367 ros::Duration lat_diff = cur->first - time;
00368 if(ear_diff > ros::Duration(joint_state_cache_allowed_difference_) &&
00369 lat_diff > ros::Duration(joint_state_cache_allowed_difference_)) {
00370 ROS_WARN("Asking for time in joint state area that's too sparse");
00371 current_joint_values_lock_.unlock();
00372 return false;
00373 } else {
00374 if(ear_diff > lat_diff) {
00375 ROS_DEBUG_STREAM("Got time later within " << lat_diff.toSec());
00376 ret_map = cur->second;
00377 break;
00378 } else {
00379 ROS_DEBUG_STREAM("Got time earlier within " << ear_diff.toSec());
00380 ret_map = next->second;
00381 break;
00382 }
00383 }
00384 }
00385 next++;
00386 cur++;
00387 }
00388 }
00389 current_joint_values_lock_.unlock();
00390 return true;
00391 }
00392
00393 void planning_environment::KinematicModelStateMonitor::waitForState(void) const
00394 {
00395 int s = 0;
00396 while (nh_.ok() && !haveState())
00397 {
00398 if (s == 0)
00399 {
00400 ROS_INFO("Waiting for robot state ...");
00401 if (!haveJointState_)
00402 ROS_INFO("Waiting for joint state ...");
00403 }
00404 s = (s + 1) % 40;
00405 ros::spinOnce();
00406 ros::Duration().fromSec(0.05).sleep();
00407 }
00408 if (haveState())
00409 ROS_INFO("Robot state received!");
00410 }
00411
00412 bool planning_environment::KinematicModelStateMonitor::isJointStateUpdated(double sec) const
00413 {
00414
00415
00416
00417
00418 if(sec < 1e-5)
00419 {
00420 return false;
00421 }
00422
00423
00424
00425
00426 if(sec > 1e-5 && lastJointStateUpdate_ > ros::TIME_MIN && ros::Time::now() < ros::Time(sec))
00427 {
00428 return true;
00429 }
00430
00431 ROS_DEBUG("Last joint update %g interval begins %g", lastJointStateUpdate_.toSec(), (ros::Time::now()-ros::Duration(sec)).toSec());
00432
00433
00434 if (lastJointStateUpdate_ < ros::Time::now()-ros::Duration(sec))
00435 {
00436 return false;
00437 }
00438
00439 return true;
00440 }
00441
00442 bool planning_environment::KinematicModelStateMonitor::isPoseUpdated(double sec) const
00443 {
00444
00445 if(sec < 1e-5)
00446 {
00447 return false;
00448 }
00449
00450
00451 if(lastPoseUpdate_ > ros::TIME_MIN && ros::Time::now() < ros::Time(sec))
00452 {
00453 return true;
00454 }
00455
00456
00457 if (lastPoseUpdate_ < ros::Time::now()-ros::Duration(sec))
00458 {
00459 return false;
00460 }
00461
00462 return true;
00463 }