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 
00038 #include <pluginlib/class_list_macros.h>
00039 #include <robot_controllers/point_head.h>
00040 
00041 #include <urdf/model.h>
00042 #include <kdl_parser/kdl_parser.hpp>
00043 
00044 PLUGINLIB_EXPORT_CLASS(robot_controllers::PointHeadController, robot_controllers::Controller)
00045 
00046 namespace robot_controllers
00047 {
00048 
00049 int PointHeadController::init(ros::NodeHandle& nh, ControllerManager* manager)
00050 {
00051   
00052   if (!manager)
00053   {
00054     initialized_ = false;
00055     return -1;
00056   }
00057 
00058   Controller::init(nh, manager);
00059   manager_ = manager;
00060 
00061   
00062   boost::mutex::scoped_lock lock(sampler_mutex_);
00063   sampler_.reset();
00064   preempted_ = false;
00065 
00066   
00067   nh.param<bool>("stop_with_action", stop_with_action_, false);
00068 
00069   
00070   head_pan_ = manager_->getJointHandle("head_pan_joint");
00071   head_tilt_ = manager_->getJointHandle("head_tilt_joint");
00072 
00073   
00074   urdf::Model model;
00075   if (!model.initParam("robot_description"))
00076   {
00077     ROS_ERROR_NAMED("PointHeadController",
00078       "Failed to parse URDF, is robot_description parameter set?");
00079     return -1;
00080   }
00081 
00082   if (!kdl_parser::treeFromUrdfModel(model, kdl_tree_))
00083   {
00084     ROS_ERROR_NAMED("PointHeadController", "Failed to construct KDL tree");
00085     return -1;
00086   }
00087 
00088   
00089   KDL::SegmentMap segment_map = kdl_tree_.getSegments();
00090   for (KDL::SegmentMap::iterator it = segment_map.begin();
00091        it != segment_map.end();
00092        ++it)
00093   {
00094 #ifdef KDL_USE_NEW_TREE_INTERFACE
00095     if (it->second->segment.getJoint().getName() == head_pan_->getName())
00096       root_link_ = it->second->parent->first;
00097 #else
00098     if (it->second.segment.getJoint().getName() == head_pan_->getName())
00099       root_link_ = it->second.parent->first;
00100 #endif
00101   }
00102 
00103   
00104   server_.reset(new head_server_t(nh, "",
00105                 boost::bind(&PointHeadController::executeCb, this, _1),
00106                 false));
00107   server_->start();
00108 
00109   initialized_ = true;
00110   return 0;
00111 }
00112 
00113 bool PointHeadController::start()
00114 {
00115   if (!initialized_)
00116   {
00117     ROS_ERROR_NAMED("PointHeadController",
00118                     "Unable to start, not initialized.");
00119     return false;
00120   }
00121 
00122   if (!server_->isActive())
00123   {
00124     ROS_ERROR_NAMED("PointHeadController",
00125                     "Unable to start, action server is not active.");
00126     return false;
00127   }
00128 
00129   return true;
00130 }
00131 
00132 bool PointHeadController::stop(bool force)
00133 {
00134   if (!initialized_)
00135     return true;
00136 
00137   if (server_->isActive())
00138   {
00139     if (force)
00140     {
00141       
00142       server_->setAborted(result_, "Controller manager forced preemption.");
00143       ROS_DEBUG_NAMED("PointHeadController",
00144                       "Controller manager forced preemption.");
00145       return true;
00146     }
00147 
00148     
00149     return false;
00150   }
00151 
00152   
00153   return true;
00154 }
00155 
00156 bool PointHeadController::reset()
00157 {
00158   stop(true);  
00159   return (manager_->requestStop(getName()) == 0);
00160 }
00161 
00162 void PointHeadController::update(const ros::Time& now, const ros::Duration& dt)
00163 {
00164   if (!initialized_)
00165     return;
00166 
00167   
00168   if (server_->isActive() && sampler_)
00169   {
00170     boost::mutex::scoped_lock lock(sampler_mutex_);
00171 
00172     
00173     TrajectoryPoint p = sampler_->sample(now.toSec());
00174     last_sample_ = p;
00175 
00176     
00177     if (now.toSec() > sampler_->end_time())
00178       server_->setSucceeded(result_, "OK");
00179 
00180     
00181     if (p.q.size() == 2)
00182     {
00183       head_pan_->setPosition(p.q[0], p.qd[0], 0.0);
00184       head_tilt_->setPosition(p.q[1], p.qd[1], 0.0);
00185     }
00186   }
00187   else if (last_sample_.q.size() == 2)
00188   {
00189     
00190     head_pan_->setPosition(last_sample_.q[0], 0.0, 0.0);
00191     head_tilt_->setPosition(last_sample_.q[1], 0.0, 0.0);
00192   }
00193 }
00194 
00195 void PointHeadController::executeCb(const control_msgs::PointHeadGoalConstPtr& goal)
00196 {
00197   float head_pan_goal_ = 0.0;
00198   float head_tilt_goal_ = 0.0;
00199   try
00200   {
00201     geometry_msgs::PointStamped target_in_pan, target_in_tilt;
00202     listener_.transformPoint(root_link_, ros::Time(0), goal->target, goal->target.header.frame_id, target_in_pan);
00203     listener_.transformPoint("head_pan_link", ros::Time(0), goal->target, goal->target.header.frame_id, target_in_tilt);
00204     head_pan_goal_ = atan2(target_in_pan.point.y, target_in_pan.point.x);
00205     head_tilt_goal_ = -atan2(target_in_tilt.point.z, sqrt(pow(target_in_tilt.point.x, 2) + pow(target_in_tilt.point.y, 2)));
00206   }
00207   catch(const tf::TransformException &ex)
00208   {
00209     server_->setAborted(result_, "Could not transform goal.");
00210     ROS_WARN_NAMED("PointHeadController", "Could not transform goal.");
00211     return;
00212   }
00213 
00214   
00215   Trajectory t;
00216   t.points.resize(2);
00217   if (preempted_)
00218   {
00219     
00220     t.points[0] = last_sample_;
00221   }
00222   else
00223   {
00224     
00225     t.points[0].q.push_back(head_pan_->getPosition());
00226     t.points[0].q.push_back(head_tilt_->getPosition());
00227     t.points[0].qd.push_back(0.0);
00228     t.points[0].qd.push_back(0.0);
00229     t.points[0].qdd.push_back(0.0);
00230     t.points[0].qdd.push_back(0.0);
00231     t.points[0].time = ros::Time::now().toSec();
00232   }
00233 
00234   
00235   t.points[1].q.push_back(head_pan_goal_);
00236   t.points[1].q.push_back(head_tilt_goal_);
00237   t.points[1].qd.push_back(0.0);
00238   t.points[1].qd.push_back(0.0);
00239   t.points[1].qdd.push_back(0.0);
00240   t.points[1].qdd.push_back(0.0);
00241 
00242   
00243   double max_pan_vel = head_pan_->getVelocityMax();
00244   double max_tilt_vel = head_tilt_->getVelocityMax();
00245   if (goal->max_velocity > 0.0)
00246   {
00247     max_pan_vel = fmin(goal->max_velocity, head_pan_->getVelocityMax());
00248     max_tilt_vel = fmin(goal->max_velocity, head_tilt_->getVelocityMax());
00249   }
00250   double pan_transit = fabs((t.points[1].q[0] - t.points[0].q[0]) / max_pan_vel);
00251   double tilt_transit = fabs((t.points[1].q[1] - t.points[0].q[1]) / max_tilt_vel);
00252   t.points[1].time = t.points[0].time + fmax(fmax(pan_transit, tilt_transit), goal->min_duration.toSec());
00253 
00254   {
00255     boost::mutex::scoped_lock lock(sampler_mutex_);
00256     sampler_.reset(new SplineTrajectorySampler(t));
00257   }
00258 
00259   if (manager_->requestStart(getName()) != 0)
00260   {
00261     server_->setAborted(result_, "Cannot point head, unable to start controller.");
00262     ROS_ERROR_NAMED("PointHeadController",
00263                     "Cannot point head, unable to start controller.");
00264     return;
00265   }
00266 
00267   preempted_ = false;
00268   while (server_->isActive())
00269   {
00270     if (server_->isPreemptRequested())
00271     {
00272       server_->setPreempted(result_, "Pointing of the head has been preempted");
00273       ROS_DEBUG_NAMED("PointHeadController",
00274                       "Pointing of the head has been preempted");
00275       preempted_ = true;
00276       break;
00277     }
00278 
00279     
00280     ros::Duration(1/50.0).sleep();
00281   }
00282 
00283   
00284   if (stop_with_action_ && !preempted_)
00285     manager_->requestStop(getName());
00286 
00287   ROS_DEBUG_NAMED("PointHeadController", "Done pointing head");
00288 }
00289 
00290 std::vector<std::string> PointHeadController::getCommandedNames()
00291 {
00292   std::vector<std::string> names;
00293   names.push_back(head_pan_->getName());
00294   names.push_back(head_tilt_->getName());
00295   return names;
00296 }
00297 
00298 std::vector<std::string> PointHeadController::getClaimedNames()
00299 {
00300   
00301   return getCommandedNames();
00302 }
00303 
00304 }