joystick_teleop.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, Fetch Robotics Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Fetch Robotics Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL FETCH ROBOTICS INC. BE LIABLE FOR ANY
21  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
26  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 // Author: Michael Ferguson, Hanjun Song
30 
31 /*
32  * This is still a work in progress
33  * In the future, each teleop component would probably be a plugin
34  */
35 
36 #include <algorithm>
37 #include <boost/thread/mutex.hpp>
38 
39 #include <ros/ros.h>
41 
42 #include <control_msgs/FollowJointTrajectoryAction.h>
43 #include <control_msgs/GripperCommandAction.h>
44 #include <geometry_msgs/TwistStamped.h>
45 #include <nav_msgs/Odometry.h>
46 #include <sensor_msgs/JointState.h>
47 #include <sensor_msgs/Joy.h>
48 #include <topic_tools/MuxSelect.h>
49 
50 double integrate(double desired, double present, double max_rate, double dt)
51 {
52  if (desired > present)
53  return std::min(desired, present + max_rate * dt);
54  else
55  return std::max(desired, present - max_rate * dt);
56 }
57 
58 
60 {
61 public:
62  TeleopComponent() : active_(false) {}
63  virtual ~TeleopComponent() {}
64 
65  // This gets called whenever new joy message comes in
66  // returns whether lower priority teleop components should be stopped
67  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
68  const sensor_msgs::JointState::ConstPtr& state) = 0;
69 
70  // This gets called at set frequency
71  virtual void publish(const ros::Duration& dt) = 0;
72 
73  // Start the component. Must be idempotent.
74  virtual bool start()
75  {
76  active_ = true;
77  return active_;
78  }
79 
80  // Stop the component. Must be idempotent.
81  virtual bool stop()
82  {
83  active_ = false;
84  return active_;
85  }
86 
87 protected:
88  bool active_;
89 };
90 
91 
93 {
94 public:
95  BaseTeleop(const std::string& name, ros::NodeHandle& nh)
96  {
97  ros::NodeHandle pnh(nh, name);
98 
99  // Button mapping
100  pnh.param("button_deadman", deadman_, 10);
101  pnh.param("axis_x", axis_x_, 3);
102  pnh.param("axis_w", axis_w_, 0);
103 
104  // Base limits
105  pnh.param("max_vel_x", max_vel_x_, 1.0);
106  pnh.param("min_vel_x", min_vel_x_, -0.5);
107  pnh.param("max_vel_w", max_vel_w_, 3.0);
108  pnh.param("max_acc_x", max_acc_x_, 1.0);
109  pnh.param("max_acc_w", max_acc_w_, 3.0);
110 
111  // Maximum windup of acceleration ramping
112  pnh.param("max_windup_time", max_windup_time, 0.25);
113 
114  // Mux for overriding navigation, etc.
115  pnh.param("use_mux", use_mux_, true);
116  if (use_mux_)
117  {
118  mux_ = nh.serviceClient<topic_tools::MuxSelect>("/cmd_vel_mux/select");
119  }
120 
121  cmd_vel_pub_ = nh.advertise<geometry_msgs::Twist>("/teleop/cmd_vel", 1);
122  odom_sub_ = nh.subscribe("/odom", 1, &BaseTeleop::odomCallback, this);
123  }
124 
125  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
126  const sensor_msgs::JointState::ConstPtr& state)
127  {
128  bool deadman_pressed = joy->buttons[deadman_];
129 
130  if (!deadman_pressed)
131  {
132  stop();
133  return false;
134  }
135 
136  start();
137 
138  if (joy->axes[axis_x_] > 0.0)
139  desired_.linear.x = joy->axes[axis_x_] * max_vel_x_;
140  else
141  desired_.linear.x = joy->axes[axis_x_] * -min_vel_x_;
142  desired_.angular.z = joy->axes[axis_w_] * max_vel_w_;
143 
144  // We are active, don't process lower priority components
145  return true;
146  }
147 
148  virtual void publish(const ros::Duration& dt)
149  {
150  if (active_)
151  {
152  {
153  boost::mutex::scoped_lock lock(odom_mutex_);
154  // Make sure base is actually keeping up with commands
155  // When accelerating (in either direction) do not continue to ramp our
156  // acceleration more than max_windup_time ahead of actually attained speeds.
157  // This is especially important if robot gets stuck.
158  if (last_.linear.x >= 0)
159  last_.linear.x = std::min(last_.linear.x, odom_.twist.twist.linear.x + max_acc_x_ * max_windup_time);
160  else
161  last_.linear.x = std::max(last_.linear.x, odom_.twist.twist.linear.x - max_acc_x_ * max_windup_time);
162  if (last_.angular.z >= 0)
163  last_.angular.z = std::min(last_.angular.z, odom_.twist.twist.angular.z + max_acc_w_ * max_windup_time);
164  else
165  last_.angular.z = std::max(last_.angular.z, odom_.twist.twist.angular.z - max_acc_w_ * max_windup_time);
166  }
167  // Ramp commands based on acceleration limits
168  last_.linear.x = integrate(desired_.linear.x, last_.linear.x, max_acc_x_, dt.toSec());
169  last_.angular.z = integrate(desired_.angular.z, last_.angular.z, max_acc_w_, dt.toSec());
170  cmd_vel_pub_.publish(last_);
171  }
172  }
173 
174  virtual bool start()
175  {
176  if (!active_ && use_mux_)
177  {
178  // Connect mux
179  topic_tools::MuxSelect req;
180  req.request.topic = cmd_vel_pub_.getTopic();
181  if (mux_.call(req))
182  {
183  prev_mux_topic_ = req.response.prev_topic;
184  }
185  else
186  {
187  ROS_ERROR("Unable to switch mux");
188  }
189  }
190  active_ = true;
191  return active_;
192  }
193 
194  virtual bool stop()
195  {
196  // Publish stop message
197  last_ = desired_ = geometry_msgs::Twist();
198  cmd_vel_pub_.publish(last_);
199  // Disconnect mux
200  if (active_ && use_mux_)
201  {
202  topic_tools::MuxSelect req;
203  req.request.topic = prev_mux_topic_;
204  if (!mux_.call(req))
205  {
206  ROS_ERROR("Unable to switch mux");
207  return active_;
208  }
209  }
210  active_ = false;
211  return active_;
212  }
213 
214 private:
215  void odomCallback(const nav_msgs::OdometryConstPtr& odom)
216  {
217  // Lock mutex on state message
218  boost::mutex::scoped_lock lock(odom_mutex_);
219  odom_ = *odom;
220  }
221 
222  // Buttons from params
223  int deadman_, axis_x_, axis_w_;
224 
225  // Limits from params
226  double max_vel_x_, min_vel_x_, max_vel_w_;
227  double max_acc_x_, max_acc_w_;
228 
229  // Support for multiplexor between teleop and application base commands
230  bool use_mux_;
231  std::string prev_mux_topic_;
233 
234  // Twist output, odometry feedback
237 
238  // Latest feedback, mutex around it
239  boost::mutex odom_mutex_;
240  nav_msgs::Odometry odom_;
241  // Maximum timestep that our ramping can get ahead of actual velocities
243 
244  geometry_msgs::Twist desired_;
245  geometry_msgs::Twist last_;
246 };
247 
248 
249 // This controls a single joint through a follow controller (for instance, torso)
251 {
253 
254 public:
255  FollowTeleop(const std::string& name, ros::NodeHandle& nh)
256  {
257  ros::NodeHandle pnh(nh, name);
258 
259  // Button mapping
260  pnh.param("button_deadman", deadman_, 10);
261  pnh.param("button_increase", inc_button_, 12);
262  pnh.param("button_decrease", dec_button_, 14);
263 
264  // Joint Limits
265  pnh.param("min_position", min_position_, 0.0);
266  pnh.param("max_position", max_position_, 0.4);
267  pnh.param("max_velocity", max_velocity_, 0.075);
268  pnh.param("max_accel", max_acceleration_, 0.25);
269 
270  // Should we inhibit lower priority components if running?
271  pnh.param("inhibit", inhibit_, false);
272 
273  // Load topic/joint info
274  pnh.param<std::string>("joint_name", joint_name_, "torso_lift_joint");
275  std::string action_name;
276  pnh.param<std::string>("action_name", action_name, "torso_controller/follow_joint_trajectory");
277 
278  client_.reset(new client_t(action_name, true));
279  if (!client_->waitForServer(ros::Duration(2.0)))
280  {
281  ROS_ERROR("%s may not be connected.", action_name.c_str());
282  }
283  }
284 
285  // This gets called whenever new joy message comes in
286  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
287  const sensor_msgs::JointState::ConstPtr& state)
288  {
289  bool deadman_pressed = joy->buttons[deadman_];
290 
291  if (!deadman_pressed)
292  {
293  stop();
294  // Update joint position
295  for (size_t i = 0; i < state->name.size(); i++)
296  {
297  if (state->name[i] == joint_name_)
298  {
299  actual_position_ = state->position[i];
300  break;
301  }
302  }
303  return false;
304  }
305 
306  if (joy->buttons[inc_button_])
307  {
308  desired_velocity_ = max_velocity_;
309  start();
310  }
311  else if (joy->buttons[dec_button_])
312  {
313  desired_velocity_ = -max_velocity_;
314  start();
315  }
316  else
317  {
318  desired_velocity_ = 0.0;
319  }
320 
321  return inhibit_;
322  }
323 
324  // This gets called at set frequency
325  virtual void publish(const ros::Duration& dt)
326  {
327  if (active_)
328  {
329  // Fill in a message (future dated at fixed time step)
330  double step = 0.25;
331  double vel = integrate(desired_velocity_, last_velocity_, max_acceleration_, step);
332  double travel = step * (vel + last_velocity_) / 2.0;
333  double pos = std::max(min_position_, std::min(max_position_, actual_position_ + travel));
334  // Send message
335  control_msgs::FollowJointTrajectoryGoal goal;
336  goal.trajectory.joint_names.push_back(joint_name_);
337  trajectory_msgs::JointTrajectoryPoint p;
338  p.positions.push_back(pos);
339  p.velocities.push_back(vel);
340  p.time_from_start = ros::Duration(step);
341  goal.trajectory.points.push_back(p);
342  goal.goal_time_tolerance = ros::Duration(0.0);
343  client_->sendGoal(goal);
344  // Update based on actual timestep
345  vel = integrate(desired_velocity_, last_velocity_, max_acceleration_, dt.toSec());
346  travel = dt.toSec() * (vel + last_velocity_) / 2.0;
347  actual_position_ = std::max(min_position_, std::min(max_position_, actual_position_ + travel));
348  last_velocity_ = vel;
349  }
350  }
351 
352  virtual bool stop()
353  {
354  active_ = false;
355  last_velocity_ = 0.0;
356  return active_;
357  }
358 
359 private:
360  int deadman_, inc_button_, dec_button_;
361  double min_position_, max_position_, max_velocity_, max_acceleration_;
362  bool inhibit_;
363  std::string joint_name_;
365  double desired_velocity_, last_velocity_;
367 };
368 
369 // Gripper Teleop
371 {
373 
374 public:
375  GripperTeleop(const std::string& name, ros::NodeHandle& nh) :
376  req_close_(false),
377  req_open_(false)
378  {
379  ros::NodeHandle pnh(nh, name);
380 
381  // Button mapping
382  pnh.param("button_deadman", deadman_, 10);
383  pnh.param("button_open", open_button_, 0);
384  pnh.param("button_close", close_button_, 3);
385 
386  // Joint Limits
387  pnh.param("closed_position", min_position_, 0.0);
388  pnh.param("open_position", max_position_, 0.115);
389  pnh.param("max_effort", max_effort_, 100.0);
390 
391  std::string action_name = "gripper_controller/gripper_action";
392  client_.reset(new client_t(action_name, true));
393  if (!client_->waitForServer(ros::Duration(2.0)))
394  {
395  ROS_ERROR("%s may not be connected.", action_name.c_str());
396  }
397  }
398 
399  // This gets called whenever new joy message comes in
400  // returns whether lower priority teleop components should be stopped
401  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
402  const sensor_msgs::JointState::ConstPtr& state)
403  {
404  bool deadman_pressed = joy->buttons[deadman_];
405 
406  if (deadman_pressed)
407  {
408  if (joy->buttons[open_button_])
409  req_open_ = true;
410  else if (joy->buttons[close_button_])
411  req_close_ = true;
412  }
413 
414  return false;
415  }
416 
417  // This gets called at set frequency
418  virtual void publish(const ros::Duration& dt)
419  {
420  if (req_open_)
421  {
422  control_msgs::GripperCommandGoal goal;
423  goal.command.position = max_position_;
424  goal.command.max_effort = max_effort_;
425  client_->sendGoal(goal);
426  req_open_ = false;
427  }
428  else if (req_close_)
429  {
430  control_msgs::GripperCommandGoal goal;
431  goal.command.position = min_position_;
432  goal.command.max_effort = max_effort_;
433  client_->sendGoal(goal);
434  req_close_ = false;
435  }
436  }
437 
438 private:
439  int deadman_, open_button_, close_button_;
440  double min_position_, max_position_, max_effort_;
441  bool req_close_, req_open_;
443 };
444 
445 
446 // Head Teleop
448 {
450 
451 public:
452  HeadTeleop(const std::string& name, ros::NodeHandle& nh) :
453  last_pan_(0.0),
454  last_tilt_(0.0)
455  {
456  ros::NodeHandle pnh(nh, name);
457 
458  // Button mapping
459  pnh.param("button_deadman", deadman_, 8);
460  pnh.param("axis_pan", axis_pan_, 0);
461  pnh.param("axis_tilt", axis_tilt_, 3);
462 
463  // Joint limits
464  pnh.param("max_vel_pan", max_vel_pan_, 1.5);
465  pnh.param("max_vel_tilt", max_vel_tilt_, 1.5);
466  pnh.param("max_acc_pan", max_acc_pan_, 3.0);
467  pnh.param("max_acc_tilt", max_acc_tilt_, 3.0);
468  pnh.param("min_pos_pan", min_pos_pan_, -1.57);
469  pnh.param("max_pos_pan", max_pos_pan_, 1.57);
470  pnh.param("min_pos_tilt", min_pos_tilt_, -0.76);
471  pnh.param("max_pos_tilt", max_pos_tilt_, 1.45);
472 
473  // TODO: load topic from params
474  head_pan_joint_ = "head_pan_joint";
475  head_tilt_joint_ = "head_tilt_joint";
476 
477  std::string action_name = "head_controller/follow_joint_trajectory";
478  client_.reset(new client_t(action_name, true));
479  if (!client_->waitForServer(ros::Duration(2.0)))
480  {
481  ROS_ERROR("%s may not be connected.", action_name.c_str());
482  }
483  }
484 
485  // This gets called whenever new joy message comes in
486  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
487  const sensor_msgs::JointState::ConstPtr& state)
488  {
489  bool deadman_pressed = joy->buttons[deadman_];
490 
491  if (!deadman_pressed)
492  {
493  stop();
494  // Update joint positions
495  for (size_t i = 0; i < state->name.size(); i++)
496  {
497  if (state->name[i] == head_pan_joint_)
498  actual_pos_pan_ = state->position[i];
499  if (state->name[i] == head_tilt_joint_)
500  actual_pos_tilt_ = state->position[i];
501  }
502  return false;
503  }
504 
505  desired_pan_ = joy->axes[axis_pan_] * max_vel_pan_;
506  desired_tilt_ = joy->axes[axis_tilt_] * max_vel_tilt_;
507  start();
508 
509  return true;
510  }
511 
512  // This gets called at set frequency
513  virtual void publish(const ros::Duration& dt)
514  {
515  if (active_)
516  {
517  // Fill in message (future dated with fixed time step)
518  double step = 0.125;
519  double pan_vel = integrate(desired_pan_, last_pan_, max_acc_pan_, step);
520  double pan_travel = step * (pan_vel + last_pan_) / 2.0;
521  double pan = std::max(min_pos_pan_, std::min(max_pos_pan_, actual_pos_pan_ + pan_travel));
522  double tilt_vel = integrate(desired_tilt_, last_tilt_, max_acc_tilt_, step);
523  double tilt_travel = step * (tilt_vel + last_tilt_) / 2.0;
524  double tilt = std::max(min_pos_tilt_, std::min(max_pos_tilt_, actual_pos_tilt_ + tilt_travel));
525  // Publish message
526  control_msgs::FollowJointTrajectoryGoal goal;
527  goal.trajectory.joint_names.push_back(head_pan_joint_);
528  goal.trajectory.joint_names.push_back(head_tilt_joint_);
529  trajectory_msgs::JointTrajectoryPoint p;
530  p.positions.push_back(pan);
531  p.positions.push_back(tilt);
532  p.velocities.push_back(pan_vel);
533  p.velocities.push_back(tilt_vel);
534  p.time_from_start = ros::Duration(step);
535  goal.trajectory.points.push_back(p);
536  goal.goal_time_tolerance = ros::Duration(0.0);
537  client_->sendGoal(goal);
538  // Update based on actual timestep
539  pan_vel = integrate(desired_pan_, last_pan_, max_acc_pan_, dt.toSec());
540  pan_travel = dt.toSec() * (pan_vel + last_pan_) / 2.0;
541  actual_pos_pan_ = std::max(min_pos_pan_, std::min(max_pos_pan_, actual_pos_pan_ + pan_travel));
542  last_pan_ = pan_vel;
543  tilt_vel = integrate(desired_tilt_, last_tilt_, max_acc_tilt_, dt.toSec());
544  tilt_travel = dt.toSec() * (tilt_vel + last_tilt_) / 2.0;
545  actual_pos_tilt_ = std::max(min_pos_tilt_, std::min(max_pos_tilt_, actual_pos_tilt_ + tilt_travel));
546  last_tilt_ = tilt_vel;
547  }
548  }
549 
550  virtual bool stop()
551  {
552  active_ = false;
553  last_pan_ = last_tilt_ = 0.0; // reset velocities
554  return active_;
555  }
556 
557 private:
558  int deadman_, axis_pan_, axis_tilt_;
559  double max_vel_pan_, max_vel_tilt_;
560  double max_acc_pan_, max_acc_tilt_;
561  double min_pos_pan_, max_pos_pan_, min_pos_tilt_, max_pos_tilt_;
562  std::string head_pan_joint_, head_tilt_joint_;
563  double actual_pos_pan_, actual_pos_tilt_; // actual positions
564  double desired_pan_, desired_tilt_; // desired velocities
565  double last_pan_, last_tilt_;
567 };
568 
570 {
571 public:
572  ArmTeleop(const std::string& name, ros::NodeHandle& nh)
573  {
574  ros::NodeHandle pnh(nh, name);
575 
576  pnh.param("axis_x", axis_x_, 3);
577  pnh.param("axis_y", axis_y_, 2);
578  pnh.param("axis_z", axis_z_, 1);
579  pnh.param("axis_roll", axis_roll_, 2);
580  pnh.param("axis_pitch", axis_pitch_, 3);
581  pnh.param("axis_yaw", axis_yaw_, 0);
582 
583  pnh.param("button_deadman", deadman_, 10);
584  pnh.param("button_arm_linear", button_linear_, 9);
585  pnh.param("button_arm_angular", button_angular_, 11);
586 
587  // Twist limits
588  pnh.param("max_vel_x", max_vel_x_, 1.0);
589  pnh.param("max_vel_y", max_vel_y_, 1.0);
590  pnh.param("max_vel_z", max_vel_z_, 1.0);
591  pnh.param("max_acc_x", max_acc_x_, 10.0);
592  pnh.param("max_acc_y", max_acc_y_, 10.0);
593  pnh.param("max_acc_z", max_acc_z_, 10.0);
594 
595  pnh.param("max_vel_roll", max_vel_roll_, 2.0);
596  pnh.param("max_vel_pitch", max_vel_pitch_, 2.0);
597  pnh.param("max_vel_yaw", max_vel_yaw_, 2.0);
598  pnh.param("max_acc_roll", max_acc_roll_, 10.0);
599  pnh.param("max_acc_pitch", max_acc_pitch_, 10.0);
600  pnh.param("max_acc_yaw", max_acc_yaw_, 10.0);
601 
602  cmd_pub_ = nh.advertise<geometry_msgs::TwistStamped>("/arm_controller/cartesian_twist/command", 10);
603  }
604 
605  virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
606  const sensor_msgs::JointState::ConstPtr& state)
607  {
608  bool deadman_pressed = joy->buttons[deadman_];
609  bool button_linear_pressed = joy->buttons[button_linear_];
610  bool button_angular_pressed = joy->buttons[button_angular_];
611 
612  if ((!(button_linear_pressed || button_angular_pressed) || !deadman_pressed) &&
613  (ros::Time::now() - last_update_ > ros::Duration(0.5)))
614  {
615  stop();
616  return false;
617  }
618 
619  start();
620 
621  if (button_linear_pressed)
622  {
623  desired_.twist.linear.x = joy->axes[axis_x_] * max_vel_x_;
624  desired_.twist.linear.y = joy->axes[axis_y_] * max_vel_y_;
625  desired_.twist.linear.z = joy->axes[axis_z_] * max_vel_z_;
626  desired_.twist.angular.x = 0.0;
627  desired_.twist.angular.y = 0.0;
628  desired_.twist.angular.z = 0.0;
629  last_update_ = ros::Time::now();
630  }
631  else if (button_angular_pressed)
632  {
633  desired_.twist.linear.x = 0.0;
634  desired_.twist.linear.y = 0.0;
635  desired_.twist.linear.z = 0.0;
636  desired_.twist.angular.x = joy->axes[axis_roll_] * max_vel_roll_;
637  desired_.twist.angular.y = joy->axes[axis_pitch_] * max_vel_pitch_;
638  desired_.twist.angular.z = joy->axes[axis_yaw_] * max_vel_yaw_;
639  last_update_ = ros::Time::now();
640  }
641  else
642  {
643  desired_.twist.linear.x = 0.0;
644  desired_.twist.linear.y = 0.0;
645  desired_.twist.linear.z = 0.0;
646  desired_.twist.angular.x = 0.0;
647  desired_.twist.angular.y = 0.0;
648  desired_.twist.angular.z = 0.0;
649  }
650 
651  return true;
652  }
653 
654  virtual void publish(const ros::Duration& dt)
655  {
656  if (active_)
657  {
658  // Ramp commands based on acceleration limits
659  last_.twist.linear.x = integrate(desired_.twist.linear.x, last_.twist.linear.x, max_acc_x_, dt.toSec());
660  last_.twist.linear.y = integrate(desired_.twist.linear.y, last_.twist.linear.y, max_acc_y_, dt.toSec());
661  last_.twist.linear.z = integrate(desired_.twist.linear.z, last_.twist.linear.z, max_acc_z_, dt.toSec());
662 
663  last_.twist.angular.x = integrate(desired_.twist.angular.x, last_.twist.angular.x, max_acc_roll_, dt.toSec());
664  last_.twist.angular.y = integrate(desired_.twist.angular.y, last_.twist.angular.y, max_acc_pitch_, dt.toSec());
665  last_.twist.angular.z = integrate(desired_.twist.angular.z, last_.twist.angular.z, max_acc_yaw_, dt.toSec());
666 
667  last_.header.frame_id = "base_link";
668 
669  cmd_pub_.publish(last_);
670  }
671  }
672 
673  virtual bool start()
674  {
675  active_ = true;
676  return active_;
677  }
678 
679 
680  virtual bool stop()
681  {
682  // Publish stop message
683  if (active_)
684  {
685  last_ = desired_ = geometry_msgs::TwistStamped();
686  cmd_pub_.publish(last_);
687  }
688 
689  active_ = false;
690  return active_;
691  }
692 
693 private:
694 
695  // Buttons from params
696  int deadman_;
697  int axis_x_, axis_y_, axis_z_, axis_roll_, axis_pitch_, axis_yaw_;
698  int button_linear_, button_angular_;
699 
700  // Limits from params
701  double max_vel_x_, max_vel_y_, max_vel_z_;
702  double max_vel_roll_, max_vel_pitch_, max_vel_yaw_;
703  double max_acc_x_, max_acc_y_, max_acc_z_;
704  double max_acc_roll_, max_acc_pitch_, max_acc_yaw_;
705 
706  // Twist output
708 
709  geometry_msgs::TwistStamped desired_;
710  geometry_msgs::TwistStamped last_;
712 };
713 
714 // This pulls all the components together
715 class Teleop
716 {
718 
719 public:
721  {
722  bool is_fetch;
723  bool use_torso;
724  bool use_gripper;
725  bool use_head;
726  bool use_arm;
727  bool use_base;
728  nh.param("is_fetch", is_fetch, true);
729  nh.param("use_torso", use_torso, true);
730  nh.param("use_gripper", use_gripper, true);
731  nh.param("use_head", use_head, true);
732  nh.param("use_arm", use_arm, true);
733  nh.param("use_base", use_base, true);
734 
735  // TODO: load these from YAML
736 
737  TeleopComponentPtr c;
738  if (is_fetch)
739  {
740  if (use_torso)
741  {
742  // Torso does not override
743  c.reset(new FollowTeleop("torso", nh));
744  components_.push_back(c);
745  }
746 
747  if (use_gripper)
748  {
749  // Gripper does not override
750  c.reset(new GripperTeleop("gripper", nh));
751  components_.push_back(c);
752  }
753 
754  if (use_head)
755  {
756  // Head overrides base
757  c.reset(new HeadTeleop("head", nh));
758  components_.push_back(c);
759  }
760 
761  if (use_arm)
762  {
763  c.reset(new ArmTeleop("arm", nh));
764  components_.push_back(c);
765  }
766  }
767 
768  if (use_base)
769  {
770  // BaseTeleop goes last
771  c.reset(new BaseTeleop("base", nh));
772  components_.push_back(c);
773  }
774 
775  state_msg_.reset(new sensor_msgs::JointState());
776  joy_sub_ = nh.subscribe("/joy", 1, &Teleop::joyCallback, this);
777  state_sub_ = nh.subscribe("/joint_states", 10, &Teleop::stateCallback, this);
778  }
779 
780  void publish(const ros::Duration& dt)
781  {
782  if (ros::Time::now() - last_update_ > ros::Duration(0.25))
783  {
784  // Timed out
785  for (size_t c = 0; c < components_.size(); c++)
786  {
787  components_[c]->stop();
788  }
789  }
790  else
791  {
792  for (size_t c = 0; c < components_.size(); c++)
793  {
794  components_[c]->publish(dt);
795  }
796  }
797  }
798 
799 private:
800  void joyCallback(const sensor_msgs::Joy::ConstPtr& msg)
801  {
802  // Lock mutex on state message
803  boost::mutex::scoped_lock lock(state_mutex_);
804 
805  bool ok = true;
806  for (size_t c = 0; c < components_.size(); c++)
807  {
808  if (ok)
809  {
810  ok &= !components_[c]->update(msg, state_msg_);
811  }
812  else
813  {
814  // supressed by a higher priority component
815  components_[c]->stop();
816  }
817  }
818  last_update_ = ros::Time::now();
819  }
820 
821  void stateCallback(const sensor_msgs::JointStateConstPtr& msg)
822  {
823  // Lock mutex on state message
824  boost::mutex::scoped_lock lock(state_mutex_);
825 
826  // Update each joint based on message
827  for (size_t msg_j = 0; msg_j < msg->name.size(); msg_j++)
828  {
829  size_t state_j;
830  for (state_j = 0; state_j < state_msg_->name.size(); state_j++)
831  {
832  if (state_msg_->name[state_j] == msg->name[msg_j])
833  {
834  state_msg_->position[state_j] = msg->position[msg_j];
835  state_msg_->velocity[state_j] = msg->velocity[msg_j];
836  break;
837  }
838  }
839  if (state_j == state_msg_->name.size())
840  {
841  // New joint
842  state_msg_->name.push_back(msg->name[msg_j]);
843  state_msg_->position.push_back(msg->position[msg_j]);
844  state_msg_->velocity.push_back(msg->velocity[msg_j]);
845  }
846  }
847  }
848 
849  std::vector<TeleopComponentPtr> components_;
851  boost::mutex state_mutex_;
852  sensor_msgs::JointStatePtr state_msg_;
854 };
855 
856 int main(int argc, char** argv)
857 {
858  ros::init(argc, argv, "teleop");
859  ros::NodeHandle n("~");
860 
861  Teleop teleop;
862  teleop.init(n);
863 
864  ros::Rate r(30.0);
865  while (ros::ok())
866  {
867  ros::spinOnce();
868  teleop.publish(ros::Duration(1/30.0));
869  r.sleep();
870  }
871 
872  return 0;
873 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
double max_acc_yaw_
virtual bool stop()
void odomCallback(const nav_msgs::OdometryConstPtr &odom)
sensor_msgs::JointStatePtr state_msg_
boost::shared_ptr< client_t > client_
double max_acc_tilt_
virtual void publish(const ros::Duration &dt)
double desired_tilt_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
virtual ~TeleopComponent()
int main(int argc, char **argv)
ros::Publisher cmd_pub_
boost::shared_ptr< TeleopComponent > TeleopComponentPtr
virtual bool stop()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ArmTeleop(const std::string &name, ros::NodeHandle &nh)
virtual bool stop()
std::string prev_mux_topic_
virtual bool stop()
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
double min_pos_tilt_
ros::ServiceClient mux_
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
ros::Subscriber state_sub_
double max_windup_time
HeadTeleop(const std::string &name, ros::NodeHandle &nh)
ros::Time last_update_
virtual void publish(const ros::Duration &dt)
std::string joint_name_
void joyCallback(const sensor_msgs::Joy::ConstPtr &msg)
boost::shared_ptr< client_t > client_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
nav_msgs::Odometry odom_
double max_vel_tilt_
void init(ros::NodeHandle &nh)
geometry_msgs::TwistStamped last_
virtual void publish(const ros::Duration &dt)
virtual bool start()
ROSCPP_DECL bool ok()
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
virtual void publish(const ros::Duration &dt)=0
void stateCallback(const sensor_msgs::JointStateConstPtr &msg)
boost::mutex state_mutex_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
virtual void publish(const ros::Duration &dt)
actionlib::SimpleActionClient< control_msgs::GripperCommandAction > client_t
double max_vel_yaw_
virtual bool start()
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)=0
double actual_pos_tilt_
ros::Subscriber odom_sub_
bool sleep()
virtual bool stop()
std::string head_tilt_joint_
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > client_t
std::vector< TeleopComponentPtr > components_
geometry_msgs::Twist desired_
boost::shared_ptr< client_t > client_
ros::Publisher cmd_vel_pub_
GripperTeleop(const std::string &name, ros::NodeHandle &nh)
geometry_msgs::TwistStamped desired_
virtual void publish(const ros::Duration &dt)
ros::Time last_update_
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > client_t
static Time now()
FollowTeleop(const std::string &name, ros::NodeHandle &nh)
double integrate(double desired, double present, double max_rate, double dt)
void publish(const ros::Duration &dt)
virtual bool start()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
geometry_msgs::Twist last_
boost::mutex odom_mutex_
BaseTeleop(const std::string &name, ros::NodeHandle &nh)


fetch_teleop
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:24:06