point_head.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fetch Robotics Inc.
5  * Copyright (c) 2013, Unbounded Robotics Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Unbounded Robotics nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // Author: Michael Ferguson
37 
40 
41 #include <urdf/model.h>
43 
45 
46 namespace robot_controllers
47 {
48 
49 int PointHeadController::init(ros::NodeHandle& nh, ControllerManager* manager)
50 {
51  // We absolutely need access to the controller manager
52  if (!manager)
53  {
54  initialized_ = false;
55  return -1;
56  }
57 
58  Controller::init(nh, manager);
59  manager_ = manager;
60 
61  // No initial sampler
62  boost::mutex::scoped_lock lock(sampler_mutex_);
63  sampler_.reset();
64  preempted_ = false;
65 
66  // Get parameters
67  nh.param<bool>("stop_with_action", stop_with_action_, false);
68 
69  // Setup Joints */
70  head_pan_ = manager_->getJointHandle("head_pan_joint");
71  head_tilt_ = manager_->getJointHandle("head_tilt_joint");
72 
73  // Parse UDRF/KDL
74  urdf::Model model;
75  if (!model.initParam("robot_description"))
76  {
77  ROS_ERROR_NAMED("PointHeadController",
78  "Failed to parse URDF, is robot_description parameter set?");
79  return -1;
80  }
81 
82  if (!kdl_parser::treeFromUrdfModel(model, kdl_tree_))
83  {
84  ROS_ERROR_NAMED("PointHeadController", "Failed to construct KDL tree");
85  return -1;
86  }
87 
88  // Find parent of pan joint
89  KDL::SegmentMap segment_map = kdl_tree_.getSegments();
90  for (KDL::SegmentMap::iterator it = segment_map.begin();
91  it != segment_map.end();
92  ++it)
93  {
94 #ifdef KDL_USE_NEW_TREE_INTERFACE
95  if (it->second->segment.getJoint().getName() == head_pan_->getName())
96  root_link_ = it->second->parent->first;
97 #else
98  if (it->second.segment.getJoint().getName() == head_pan_->getName())
99  root_link_ = it->second.parent->first;
100 #endif
101  }
102 
103  // Start action server
104  server_.reset(new head_server_t(nh, "",
105  boost::bind(&PointHeadController::executeCb, this, _1),
106  false));
107  server_->start();
108 
109  initialized_ = true;
110  return 0;
111 }
112 
113 bool PointHeadController::start()
114 {
115  if (!initialized_)
116  {
117  ROS_ERROR_NAMED("PointHeadController",
118  "Unable to start, not initialized.");
119  return false;
120  }
121 
122  if (!server_->isActive())
123  {
124  ROS_ERROR_NAMED("PointHeadController",
125  "Unable to start, action server is not active.");
126  return false;
127  }
128 
129  return true;
130 }
131 
132 bool PointHeadController::stop(bool force)
133 {
134  if (!initialized_)
135  return true;
136 
137  if (server_->isActive())
138  {
139  if (force)
140  {
141  // Shut down the action
142  server_->setAborted(result_, "Controller manager forced preemption.");
143  ROS_DEBUG_NAMED("PointHeadController",
144  "Controller manager forced preemption.");
145  return true;
146  }
147 
148  // Do not abort unless forced
149  return false;
150  }
151 
152  // Just holding position, go ahead and stop us
153  return true;
154 }
155 
156 bool PointHeadController::reset()
157 {
158  stop(true); // force stop ourselves
159  return (manager_->requestStop(getName()) == 0);
160 }
161 
162 void PointHeadController::update(const ros::Time& now, const ros::Duration& dt)
163 {
164  if (!initialized_)
165  return;
166 
167  // We have a trajectory to execute?
168  if (server_->isActive() && sampler_)
169  {
170  boost::mutex::scoped_lock lock(sampler_mutex_);
171 
172  // Interpolate trajectory
173  TrajectoryPoint p = sampler_->sample(now.toSec());
174  last_sample_ = p;
175 
176  // Are we done?
177  if (now.toSec() > sampler_->end_time())
178  server_->setSucceeded(result_, "OK");
179 
180  // Send trajectory to joints
181  if (p.q.size() == 2)
182  {
183  head_pan_->setPosition(p.q[0], p.qd[0], 0.0);
184  head_tilt_->setPosition(p.q[1], p.qd[1], 0.0);
185  }
186  }
187  else if (last_sample_.q.size() == 2)
188  {
189  // Hold Position
190  head_pan_->setPosition(last_sample_.q[0], 0.0, 0.0);
191  head_tilt_->setPosition(last_sample_.q[1], 0.0, 0.0);
192  }
193 }
194 
195 void PointHeadController::executeCb(const control_msgs::PointHeadGoalConstPtr& goal)
196 {
197  float head_pan_goal_ = 0.0;
198  float head_tilt_goal_ = 0.0;
199  try
200  {
201  geometry_msgs::PointStamped target_in_pan, target_in_tilt;
202  listener_.transformPoint(root_link_, ros::Time(0), goal->target, goal->target.header.frame_id, target_in_pan);
203  listener_.transformPoint("head_pan_link", ros::Time(0), goal->target, goal->target.header.frame_id, target_in_tilt);
204  head_pan_goal_ = atan2(target_in_pan.point.y, target_in_pan.point.x);
205  head_tilt_goal_ = -atan2(target_in_tilt.point.z, sqrt(pow(target_in_tilt.point.x, 2) + pow(target_in_tilt.point.y, 2)));
206  }
207  catch(const tf::TransformException &ex)
208  {
209  server_->setAborted(result_, "Could not transform goal.");
210  ROS_WARN_NAMED("PointHeadController", "Could not transform goal.");
211  return;
212  }
213 
214  // Turn goal into a trajectory
215  Trajectory t;
216  t.points.resize(2);
217  if (preempted_)
218  {
219  // Starting point is last sample
220  t.points[0] = last_sample_;
221  }
222  else
223  {
224  // Starting point is current position, assume not moving
225  t.points[0].q.push_back(head_pan_->getPosition());
226  t.points[0].q.push_back(head_tilt_->getPosition());
227  t.points[0].qd.push_back(0.0);
228  t.points[0].qd.push_back(0.0);
229  t.points[0].qdd.push_back(0.0);
230  t.points[0].qdd.push_back(0.0);
231  t.points[0].time = ros::Time::now().toSec();
232  }
233 
234  // Ending point is goal position, not moving
235  t.points[1].q.push_back(head_pan_goal_);
236  t.points[1].q.push_back(head_tilt_goal_);
237  t.points[1].qd.push_back(0.0);
238  t.points[1].qd.push_back(0.0);
239  t.points[1].qdd.push_back(0.0);
240  t.points[1].qdd.push_back(0.0);
241 
242  // Determine how long to take to execute this trajectory
243  double max_pan_vel = head_pan_->getVelocityMax();
244  double max_tilt_vel = head_tilt_->getVelocityMax();
245  if (goal->max_velocity > 0.0)
246  {
247  max_pan_vel = fmin(goal->max_velocity, head_pan_->getVelocityMax());
248  max_tilt_vel = fmin(goal->max_velocity, head_tilt_->getVelocityMax());
249  }
250  double pan_transit = fabs((t.points[1].q[0] - t.points[0].q[0]) / max_pan_vel);
251  double tilt_transit = fabs((t.points[1].q[1] - t.points[0].q[1]) / max_tilt_vel);
252  t.points[1].time = t.points[0].time + fmax(fmax(pan_transit, tilt_transit), goal->min_duration.toSec());
253 
254  {
255  boost::mutex::scoped_lock lock(sampler_mutex_);
256  sampler_.reset(new SplineTrajectorySampler(t));
257  }
258 
259  if (manager_->requestStart(getName()) != 0)
260  {
261  server_->setAborted(result_, "Cannot point head, unable to start controller.");
262  ROS_ERROR_NAMED("PointHeadController",
263  "Cannot point head, unable to start controller.");
264  return;
265  }
266 
267  preempted_ = false;
268  while (server_->isActive())
269  {
270  if (server_->isPreemptRequested())
271  {
272  server_->setPreempted(result_, "Pointing of the head has been preempted");
273  ROS_DEBUG_NAMED("PointHeadController",
274  "Pointing of the head has been preempted");
275  preempted_ = true;
276  break;
277  }
278 
279  // No feedback needed for PointHeadAction
280  ros::Duration(1/50.0).sleep();
281  }
282 
283  // Stop this controller if desired (and not preempted)
284  if (stop_with_action_ && !preempted_)
285  manager_->requestStop(getName());
286 
287  ROS_DEBUG_NAMED("PointHeadController", "Done pointing head");
288 }
289 
290 std::vector<std::string> PointHeadController::getCommandedNames()
291 {
292  std::vector<std::string> names;
293  names.push_back(head_pan_->getName());
294  names.push_back(head_tilt_->getName());
295  return names;
296 }
297 
298 std::vector<std::string> PointHeadController::getClaimedNames()
299 {
300  // Claimed == commanded.
301  return getCommandedNames();
302 }
303 
304 } // namespace robot_controllers
Basis for a Trajectory Point.
Definition: trajectory.h:51
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
#define ROS_WARN_NAMED(name,...)
std::vector< TrajectoryPoint > points
Definition: trajectory.h:61
bool sleep() const
std::string getName(void *handle)
std::map< std::string, TreeElement > SegmentMap
#define ROS_DEBUG_NAMED(name,...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::vector< double > qd
Definition: trajectory.h:54
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
URDF_EXPORT bool initParam(const std::string &param)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
std::vector< double > q
Definition: trajectory.h:53
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define ROS_ERROR_NAMED(name,...)
static Time now()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39