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 #include <algorithm>
00037 #include <boost/thread/mutex.hpp>
00038
00039 #include <ros/ros.h>
00040 #include <actionlib/client/simple_action_client.h>
00041
00042 #include <control_msgs/FollowJointTrajectoryAction.h>
00043 #include <control_msgs/GripperCommandAction.h>
00044 #include <geometry_msgs/TwistStamped.h>
00045 #include <nav_msgs/Odometry.h>
00046 #include <sensor_msgs/JointState.h>
00047 #include <sensor_msgs/Joy.h>
00048 #include <topic_tools/MuxSelect.h>
00049
00050 double integrate(double desired, double present, double max_rate, double dt)
00051 {
00052 if (desired > present)
00053 return std::min(desired, present + max_rate * dt);
00054 else
00055 return std::max(desired, present - max_rate * dt);
00056 }
00057
00058
00059 class TeleopComponent
00060 {
00061 public:
00062 TeleopComponent() : active_(false) {}
00063 virtual ~TeleopComponent() {}
00064
00065
00066
00067 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00068 const sensor_msgs::JointState::ConstPtr& state) = 0;
00069
00070
00071 virtual void publish(const ros::Duration& dt) = 0;
00072
00073
00074 virtual bool start()
00075 {
00076 active_ = true;
00077 return active_;
00078 }
00079
00080
00081 virtual bool stop()
00082 {
00083 active_ = false;
00084 return active_;
00085 }
00086
00087 protected:
00088 bool active_;
00089 };
00090
00091
00092 class BaseTeleop : public TeleopComponent
00093 {
00094 public:
00095 BaseTeleop(const std::string& name, ros::NodeHandle& nh)
00096 {
00097 ros::NodeHandle pnh(nh, name);
00098
00099
00100 pnh.param("button_deadman", deadman_, 10);
00101 pnh.param("axis_x", axis_x_, 3);
00102 pnh.param("axis_w", axis_w_, 0);
00103
00104
00105 pnh.param("max_vel_x", max_vel_x_, 1.0);
00106 pnh.param("min_vel_x", min_vel_x_, -0.5);
00107 pnh.param("max_vel_w", max_vel_w_, 3.0);
00108 pnh.param("max_acc_x", max_acc_x_, 1.0);
00109 pnh.param("max_acc_w", max_acc_w_, 3.0);
00110
00111
00112 pnh.param("max_windup_time", max_windup_time, 0.25);
00113
00114
00115 pnh.param("use_mux", use_mux_, true);
00116 if (use_mux_)
00117 {
00118 mux_ = nh.serviceClient<topic_tools::MuxSelect>("/cmd_vel_mux/select");
00119 }
00120
00121 cmd_vel_pub_ = nh.advertise<geometry_msgs::Twist>("/teleop/cmd_vel", 1);
00122 odom_sub_ = nh.subscribe("/odom", 1, &BaseTeleop::odomCallback, this);
00123 }
00124
00125 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00126 const sensor_msgs::JointState::ConstPtr& state)
00127 {
00128 bool deadman_pressed = joy->buttons[deadman_];
00129
00130 if (!deadman_pressed)
00131 {
00132 stop();
00133 return false;
00134 }
00135
00136 start();
00137
00138 if (joy->axes[axis_x_] > 0.0)
00139 desired_.linear.x = joy->axes[axis_x_] * max_vel_x_;
00140 else
00141 desired_.linear.x = joy->axes[axis_x_] * -min_vel_x_;
00142 desired_.angular.z = joy->axes[axis_w_] * max_vel_w_;
00143
00144
00145 return true;
00146 }
00147
00148 virtual void publish(const ros::Duration& dt)
00149 {
00150 if (active_)
00151 {
00152 {
00153 boost::mutex::scoped_lock lock(odom_mutex_);
00154
00155
00156
00157
00158 if (last_.linear.x >= 0)
00159 last_.linear.x = std::min(last_.linear.x, odom_.twist.twist.linear.x + max_acc_x_ * max_windup_time);
00160 else
00161 last_.linear.x = std::max(last_.linear.x, odom_.twist.twist.linear.x - max_acc_x_ * max_windup_time);
00162 if (last_.angular.z >= 0)
00163 last_.angular.z = std::min(last_.angular.z, odom_.twist.twist.angular.z + max_acc_w_ * max_windup_time);
00164 else
00165 last_.angular.z = std::max(last_.angular.z, odom_.twist.twist.angular.z - max_acc_w_ * max_windup_time);
00166 }
00167
00168 last_.linear.x = integrate(desired_.linear.x, last_.linear.x, max_acc_x_, dt.toSec());
00169 last_.angular.z = integrate(desired_.angular.z, last_.angular.z, max_acc_w_, dt.toSec());
00170 cmd_vel_pub_.publish(last_);
00171 }
00172 }
00173
00174 virtual bool start()
00175 {
00176 if (!active_ && use_mux_)
00177 {
00178
00179 topic_tools::MuxSelect req;
00180 req.request.topic = cmd_vel_pub_.getTopic();
00181 if (mux_.call(req))
00182 {
00183 prev_mux_topic_ = req.response.prev_topic;
00184 }
00185 else
00186 {
00187 ROS_ERROR("Unable to switch mux");
00188 }
00189 }
00190 active_ = true;
00191 return active_;
00192 }
00193
00194 virtual bool stop()
00195 {
00196
00197 last_ = desired_ = geometry_msgs::Twist();
00198 cmd_vel_pub_.publish(last_);
00199
00200 if (active_ && use_mux_)
00201 {
00202 topic_tools::MuxSelect req;
00203 req.request.topic = prev_mux_topic_;
00204 if (!mux_.call(req))
00205 {
00206 ROS_ERROR("Unable to switch mux");
00207 return active_;
00208 }
00209 }
00210 active_ = false;
00211 return active_;
00212 }
00213
00214 private:
00215 void odomCallback(const nav_msgs::OdometryConstPtr& odom)
00216 {
00217
00218 boost::mutex::scoped_lock lock(odom_mutex_);
00219 odom_ = *odom;
00220 }
00221
00222
00223 int deadman_, axis_x_, axis_w_;
00224
00225
00226 double max_vel_x_, min_vel_x_, max_vel_w_;
00227 double max_acc_x_, max_acc_w_;
00228
00229
00230 bool use_mux_;
00231 std::string prev_mux_topic_;
00232 ros::ServiceClient mux_;
00233
00234
00235 ros::Publisher cmd_vel_pub_;
00236 ros::Subscriber odom_sub_;
00237
00238
00239 boost::mutex odom_mutex_;
00240 nav_msgs::Odometry odom_;
00241
00242 double max_windup_time;
00243
00244 geometry_msgs::Twist desired_;
00245 geometry_msgs::Twist last_;
00246 };
00247
00248
00249
00250 class FollowTeleop : public TeleopComponent
00251 {
00252 typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> client_t;
00253
00254 public:
00255 FollowTeleop(const std::string& name, ros::NodeHandle& nh)
00256 {
00257 ros::NodeHandle pnh(nh, name);
00258
00259
00260 pnh.param("button_deadman", deadman_, 10);
00261 pnh.param("button_increase", inc_button_, 12);
00262 pnh.param("button_decrease", dec_button_, 14);
00263
00264
00265 pnh.param("min_position", min_position_, 0.0);
00266 pnh.param("max_position", max_position_, 0.4);
00267 pnh.param("max_velocity", max_velocity_, 0.075);
00268 pnh.param("max_accel", max_acceleration_, 0.25);
00269
00270
00271 pnh.param("inhibit", inhibit_, false);
00272
00273
00274 pnh.param<std::string>("joint_name", joint_name_, "torso_lift_joint");
00275 std::string action_name;
00276 pnh.param<std::string>("action_name", action_name, "torso_controller/follow_joint_trajectory");
00277
00278 client_.reset(new client_t(action_name, true));
00279 if (!client_->waitForServer(ros::Duration(2.0)))
00280 {
00281 ROS_ERROR("%s may not be connected.", action_name.c_str());
00282 }
00283 }
00284
00285
00286 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00287 const sensor_msgs::JointState::ConstPtr& state)
00288 {
00289 bool deadman_pressed = joy->buttons[deadman_];
00290
00291 if (!deadman_pressed)
00292 {
00293 stop();
00294
00295 for (size_t i = 0; i < state->name.size(); i++)
00296 {
00297 if (state->name[i] == joint_name_)
00298 {
00299 actual_position_ = state->position[i];
00300 break;
00301 }
00302 }
00303 return false;
00304 }
00305
00306 if (joy->buttons[inc_button_])
00307 {
00308 desired_velocity_ = max_velocity_;
00309 start();
00310 }
00311 else if (joy->buttons[dec_button_])
00312 {
00313 desired_velocity_ = -max_velocity_;
00314 start();
00315 }
00316 else
00317 {
00318 desired_velocity_ = 0.0;
00319 }
00320
00321 return inhibit_;
00322 }
00323
00324
00325 virtual void publish(const ros::Duration& dt)
00326 {
00327 if (active_)
00328 {
00329
00330 double step = 0.25;
00331 double vel = integrate(desired_velocity_, last_velocity_, max_acceleration_, step);
00332 double travel = step * (vel + last_velocity_) / 2.0;
00333 double pos = std::max(min_position_, std::min(max_position_, actual_position_ + travel));
00334
00335 control_msgs::FollowJointTrajectoryGoal goal;
00336 goal.trajectory.joint_names.push_back(joint_name_);
00337 trajectory_msgs::JointTrajectoryPoint p;
00338 p.positions.push_back(pos);
00339 p.velocities.push_back(vel);
00340 p.time_from_start = ros::Duration(step);
00341 goal.trajectory.points.push_back(p);
00342 goal.goal_time_tolerance = ros::Duration(0.0);
00343 client_->sendGoal(goal);
00344
00345 vel = integrate(desired_velocity_, last_velocity_, max_acceleration_, dt.toSec());
00346 travel = dt.toSec() * (vel + last_velocity_) / 2.0;
00347 actual_position_ = std::max(min_position_, std::min(max_position_, actual_position_ + travel));
00348 last_velocity_ = vel;
00349 }
00350 }
00351
00352 virtual bool stop()
00353 {
00354 active_ = false;
00355 last_velocity_ = 0.0;
00356 return active_;
00357 }
00358
00359 private:
00360 int deadman_, inc_button_, dec_button_;
00361 double min_position_, max_position_, max_velocity_, max_acceleration_;
00362 bool inhibit_;
00363 std::string joint_name_;
00364 double actual_position_;
00365 double desired_velocity_, last_velocity_;
00366 boost::shared_ptr<client_t> client_;
00367 };
00368
00369
00370 class GripperTeleop : public TeleopComponent
00371 {
00372 typedef actionlib::SimpleActionClient<control_msgs::GripperCommandAction> client_t;
00373
00374 public:
00375 GripperTeleop(const std::string& name, ros::NodeHandle& nh) :
00376 req_close_(false),
00377 req_open_(false)
00378 {
00379 ros::NodeHandle pnh(nh, name);
00380
00381
00382 pnh.param("button_deadman", deadman_, 10);
00383 pnh.param("button_open", open_button_, 0);
00384 pnh.param("button_close", close_button_, 3);
00385
00386
00387 pnh.param("closed_position", min_position_, 0.0);
00388 pnh.param("open_position", max_position_, 0.115);
00389 pnh.param("max_effort", max_effort_, 100.0);
00390
00391 std::string action_name = "gripper_controller/gripper_action";
00392 client_.reset(new client_t(action_name, true));
00393 if (!client_->waitForServer(ros::Duration(2.0)))
00394 {
00395 ROS_ERROR("%s may not be connected.", action_name.c_str());
00396 }
00397 }
00398
00399
00400
00401 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00402 const sensor_msgs::JointState::ConstPtr& state)
00403 {
00404 bool deadman_pressed = joy->buttons[deadman_];
00405
00406 if (deadman_pressed)
00407 {
00408 if (joy->buttons[open_button_])
00409 req_open_ = true;
00410 else if (joy->buttons[close_button_])
00411 req_close_ = true;
00412 }
00413
00414 return false;
00415 }
00416
00417
00418 virtual void publish(const ros::Duration& dt)
00419 {
00420 if (req_open_)
00421 {
00422 control_msgs::GripperCommandGoal goal;
00423 goal.command.position = max_position_;
00424 goal.command.max_effort = max_effort_;
00425 client_->sendGoal(goal);
00426 req_open_ = false;
00427 }
00428 else if (req_close_)
00429 {
00430 control_msgs::GripperCommandGoal goal;
00431 goal.command.position = min_position_;
00432 goal.command.max_effort = max_effort_;
00433 client_->sendGoal(goal);
00434 req_close_ = false;
00435 }
00436 }
00437
00438 private:
00439 int deadman_, open_button_, close_button_;
00440 double min_position_, max_position_, max_effort_;
00441 bool req_close_, req_open_;
00442 boost::shared_ptr<client_t> client_;
00443 };
00444
00445
00446
00447 class HeadTeleop : public TeleopComponent
00448 {
00449 typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> client_t;
00450
00451 public:
00452 HeadTeleop(const std::string& name, ros::NodeHandle& nh) :
00453 last_pan_(0.0),
00454 last_tilt_(0.0)
00455 {
00456 ros::NodeHandle pnh(nh, name);
00457
00458
00459 pnh.param("button_deadman", deadman_, 8);
00460 pnh.param("axis_pan", axis_pan_, 0);
00461 pnh.param("axis_tilt", axis_tilt_, 3);
00462
00463
00464 pnh.param("max_vel_pan", max_vel_pan_, 1.5);
00465 pnh.param("max_vel_tilt", max_vel_tilt_, 1.5);
00466 pnh.param("max_acc_pan", max_acc_pan_, 3.0);
00467 pnh.param("max_acc_tilt", max_acc_tilt_, 3.0);
00468 pnh.param("min_pos_pan", min_pos_pan_, -1.57);
00469 pnh.param("max_pos_pan", max_pos_pan_, 1.57);
00470 pnh.param("min_pos_tilt", min_pos_tilt_, -0.76);
00471 pnh.param("max_pos_tilt", max_pos_tilt_, 1.45);
00472
00473
00474 head_pan_joint_ = "head_pan_joint";
00475 head_tilt_joint_ = "head_tilt_joint";
00476
00477 std::string action_name = "head_controller/follow_joint_trajectory";
00478 client_.reset(new client_t(action_name, true));
00479 if (!client_->waitForServer(ros::Duration(2.0)))
00480 {
00481 ROS_ERROR("%s may not be connected.", action_name.c_str());
00482 }
00483 }
00484
00485
00486 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00487 const sensor_msgs::JointState::ConstPtr& state)
00488 {
00489 bool deadman_pressed = joy->buttons[deadman_];
00490
00491 if (!deadman_pressed)
00492 {
00493 stop();
00494
00495 for (size_t i = 0; i < state->name.size(); i++)
00496 {
00497 if (state->name[i] == head_pan_joint_)
00498 actual_pos_pan_ = state->position[i];
00499 if (state->name[i] == head_tilt_joint_)
00500 actual_pos_tilt_ = state->position[i];
00501 }
00502 return false;
00503 }
00504
00505 desired_pan_ = joy->axes[axis_pan_] * max_vel_pan_;
00506 desired_tilt_ = joy->axes[axis_tilt_] * max_vel_tilt_;
00507 start();
00508
00509 return true;
00510 }
00511
00512
00513 virtual void publish(const ros::Duration& dt)
00514 {
00515 if (active_)
00516 {
00517
00518 double step = 0.125;
00519 double pan_vel = integrate(desired_pan_, last_pan_, max_acc_pan_, step);
00520 double pan_travel = step * (pan_vel + last_pan_) / 2.0;
00521 double pan = std::max(min_pos_pan_, std::min(max_pos_pan_, actual_pos_pan_ + pan_travel));
00522 double tilt_vel = integrate(desired_tilt_, last_tilt_, max_acc_tilt_, step);
00523 double tilt_travel = step * (tilt_vel + last_tilt_) / 2.0;
00524 double tilt = std::max(min_pos_tilt_, std::min(max_pos_tilt_, actual_pos_tilt_ + tilt_travel));
00525
00526 control_msgs::FollowJointTrajectoryGoal goal;
00527 goal.trajectory.joint_names.push_back(head_pan_joint_);
00528 goal.trajectory.joint_names.push_back(head_tilt_joint_);
00529 trajectory_msgs::JointTrajectoryPoint p;
00530 p.positions.push_back(pan);
00531 p.positions.push_back(tilt);
00532 p.velocities.push_back(pan_vel);
00533 p.velocities.push_back(tilt_vel);
00534 p.time_from_start = ros::Duration(step);
00535 goal.trajectory.points.push_back(p);
00536 goal.goal_time_tolerance = ros::Duration(0.0);
00537 client_->sendGoal(goal);
00538
00539 pan_vel = integrate(desired_pan_, last_pan_, max_acc_pan_, dt.toSec());
00540 pan_travel = dt.toSec() * (pan_vel + last_pan_) / 2.0;
00541 actual_pos_pan_ = std::max(min_pos_pan_, std::min(max_pos_pan_, actual_pos_pan_ + pan_travel));
00542 last_pan_ = pan_vel;
00543 tilt_vel = integrate(desired_tilt_, last_tilt_, max_acc_tilt_, dt.toSec());
00544 tilt_travel = dt.toSec() * (tilt_vel + last_tilt_) / 2.0;
00545 actual_pos_tilt_ = std::max(min_pos_tilt_, std::min(max_pos_tilt_, actual_pos_tilt_ + tilt_travel));
00546 last_tilt_ = tilt_vel;
00547 }
00548 }
00549
00550 virtual bool stop()
00551 {
00552 active_ = false;
00553 last_pan_ = last_tilt_ = 0.0;
00554 return active_;
00555 }
00556
00557 private:
00558 int deadman_, axis_pan_, axis_tilt_;
00559 double max_vel_pan_, max_vel_tilt_;
00560 double max_acc_pan_, max_acc_tilt_;
00561 double min_pos_pan_, max_pos_pan_, min_pos_tilt_, max_pos_tilt_;
00562 std::string head_pan_joint_, head_tilt_joint_;
00563 double actual_pos_pan_, actual_pos_tilt_;
00564 double desired_pan_, desired_tilt_;
00565 double last_pan_, last_tilt_;
00566 boost::shared_ptr<client_t> client_;
00567 };
00568
00569 class ArmTeleop : public TeleopComponent
00570 {
00571 public:
00572 ArmTeleop(const std::string& name, ros::NodeHandle& nh)
00573 {
00574 ros::NodeHandle pnh(nh, name);
00575
00576 pnh.param("axis_x", axis_x_, 3);
00577 pnh.param("axis_y", axis_y_, 2);
00578 pnh.param("axis_z", axis_z_, 1);
00579 pnh.param("axis_roll", axis_roll_, 2);
00580 pnh.param("axis_pitch", axis_pitch_, 3);
00581 pnh.param("axis_yaw", axis_yaw_, 0);
00582
00583 pnh.param("button_deadman", deadman_, 10);
00584 pnh.param("button_arm_linear", button_linear_, 9);
00585 pnh.param("button_arm_angular", button_angular_, 11);
00586
00587
00588 pnh.param("max_vel_x", max_vel_x_, 1.0);
00589 pnh.param("max_vel_y", max_vel_y_, 1.0);
00590 pnh.param("max_vel_z", max_vel_z_, 1.0);
00591 pnh.param("max_acc_x", max_acc_x_, 10.0);
00592 pnh.param("max_acc_y", max_acc_y_, 10.0);
00593 pnh.param("max_acc_z", max_acc_z_, 10.0);
00594
00595 pnh.param("max_vel_roll", max_vel_roll_, 2.0);
00596 pnh.param("max_vel_pitch", max_vel_pitch_, 2.0);
00597 pnh.param("max_vel_yaw", max_vel_yaw_, 2.0);
00598 pnh.param("max_acc_roll", max_acc_roll_, 10.0);
00599 pnh.param("max_acc_pitch", max_acc_pitch_, 10.0);
00600 pnh.param("max_acc_yaw", max_acc_yaw_, 10.0);
00601
00602 cmd_pub_ = nh.advertise<geometry_msgs::TwistStamped>("/arm_controller/cartesian_twist/command", 10);
00603 }
00604
00605 virtual bool update(const sensor_msgs::Joy::ConstPtr& joy,
00606 const sensor_msgs::JointState::ConstPtr& state)
00607 {
00608 bool deadman_pressed = joy->buttons[deadman_];
00609 bool button_linear_pressed = joy->buttons[button_linear_];
00610 bool button_angular_pressed = joy->buttons[button_angular_];
00611
00612 if ((!(button_linear_pressed || button_angular_pressed) || !deadman_pressed) &&
00613 (ros::Time::now() - last_update_ > ros::Duration(0.5)))
00614 {
00615 stop();
00616 return false;
00617 }
00618
00619 start();
00620
00621 if (button_linear_pressed)
00622 {
00623 desired_.twist.linear.x = joy->axes[axis_x_] * max_vel_x_;
00624 desired_.twist.linear.y = joy->axes[axis_y_] * max_vel_y_;
00625 desired_.twist.linear.z = joy->axes[axis_z_] * max_vel_z_;
00626 desired_.twist.angular.x = 0.0;
00627 desired_.twist.angular.y = 0.0;
00628 desired_.twist.angular.z = 0.0;
00629 last_update_ = ros::Time::now();
00630 }
00631 else if (button_angular_pressed)
00632 {
00633 desired_.twist.linear.x = 0.0;
00634 desired_.twist.linear.y = 0.0;
00635 desired_.twist.linear.z = 0.0;
00636 desired_.twist.angular.x = joy->axes[axis_roll_] * max_vel_roll_;
00637 desired_.twist.angular.y = joy->axes[axis_pitch_] * max_vel_pitch_;
00638 desired_.twist.angular.z = joy->axes[axis_yaw_] * max_vel_yaw_;
00639 last_update_ = ros::Time::now();
00640 }
00641 else
00642 {
00643 desired_.twist.linear.x = 0.0;
00644 desired_.twist.linear.y = 0.0;
00645 desired_.twist.linear.z = 0.0;
00646 desired_.twist.angular.x = 0.0;
00647 desired_.twist.angular.y = 0.0;
00648 desired_.twist.angular.z = 0.0;
00649 }
00650
00651 return true;
00652 }
00653
00654 virtual void publish(const ros::Duration& dt)
00655 {
00656 if (active_)
00657 {
00658
00659 last_.twist.linear.x = integrate(desired_.twist.linear.x, last_.twist.linear.x, max_acc_x_, dt.toSec());
00660 last_.twist.linear.y = integrate(desired_.twist.linear.y, last_.twist.linear.y, max_acc_y_, dt.toSec());
00661 last_.twist.linear.z = integrate(desired_.twist.linear.z, last_.twist.linear.z, max_acc_z_, dt.toSec());
00662
00663 last_.twist.angular.x = integrate(desired_.twist.angular.x, last_.twist.angular.x, max_acc_roll_, dt.toSec());
00664 last_.twist.angular.y = integrate(desired_.twist.angular.y, last_.twist.angular.y, max_acc_pitch_, dt.toSec());
00665 last_.twist.angular.z = integrate(desired_.twist.angular.z, last_.twist.angular.z, max_acc_yaw_, dt.toSec());
00666
00667 last_.header.frame_id = "base_link";
00668
00669 cmd_pub_.publish(last_);
00670 }
00671 }
00672
00673 virtual bool start()
00674 {
00675 active_ = true;
00676 return active_;
00677 }
00678
00679
00680 virtual bool stop()
00681 {
00682
00683 if (active_)
00684 {
00685 last_ = desired_ = geometry_msgs::TwistStamped();
00686 cmd_pub_.publish(last_);
00687 }
00688
00689 active_ = false;
00690 return active_;
00691 }
00692
00693 private:
00694
00695
00696 int deadman_;
00697 int axis_x_, axis_y_, axis_z_, axis_roll_, axis_pitch_, axis_yaw_;
00698 int button_linear_, button_angular_;
00699
00700
00701 double max_vel_x_, max_vel_y_, max_vel_z_;
00702 double max_vel_roll_, max_vel_pitch_, max_vel_yaw_;
00703 double max_acc_x_, max_acc_y_, max_acc_z_;
00704 double max_acc_roll_, max_acc_pitch_, max_acc_yaw_;
00705
00706
00707 ros::Publisher cmd_pub_;
00708
00709 geometry_msgs::TwistStamped desired_;
00710 geometry_msgs::TwistStamped last_;
00711 ros::Time last_update_;
00712 };
00713
00714
00715 class Teleop
00716 {
00717 typedef boost::shared_ptr<TeleopComponent> TeleopComponentPtr;
00718
00719 public:
00720 void init(ros::NodeHandle& nh)
00721 {
00722 bool is_fetch;
00723 bool use_torso;
00724 bool use_gripper;
00725 bool use_head;
00726 bool use_arm;
00727 bool use_base;
00728 nh.param("is_fetch", is_fetch, true);
00729 nh.param("use_torso", use_torso, true);
00730 nh.param("use_gripper", use_gripper, true);
00731 nh.param("use_head", use_head, true);
00732 nh.param("use_arm", use_arm, true);
00733 nh.param("use_base", use_base, true);
00734
00735
00736
00737 TeleopComponentPtr c;
00738 if (is_fetch)
00739 {
00740 if (use_torso)
00741 {
00742
00743 c.reset(new FollowTeleop("torso", nh));
00744 components_.push_back(c);
00745 }
00746
00747 if (use_gripper)
00748 {
00749
00750 c.reset(new GripperTeleop("gripper", nh));
00751 components_.push_back(c);
00752 }
00753
00754 if (use_head)
00755 {
00756
00757 c.reset(new HeadTeleop("head", nh));
00758 components_.push_back(c);
00759 }
00760
00761 if (use_arm)
00762 {
00763 c.reset(new ArmTeleop("arm", nh));
00764 components_.push_back(c);
00765 }
00766 }
00767
00768 if (use_base)
00769 {
00770
00771 c.reset(new BaseTeleop("base", nh));
00772 components_.push_back(c);
00773 }
00774
00775 state_msg_.reset(new sensor_msgs::JointState());
00776 joy_sub_ = nh.subscribe("/joy", 1, &Teleop::joyCallback, this);
00777 state_sub_ = nh.subscribe("/joint_states", 10, &Teleop::stateCallback, this);
00778 }
00779
00780 void publish(const ros::Duration& dt)
00781 {
00782 if (ros::Time::now() - last_update_ > ros::Duration(0.25))
00783 {
00784
00785 for (size_t c = 0; c < components_.size(); c++)
00786 {
00787 components_[c]->stop();
00788 }
00789 }
00790 else
00791 {
00792 for (size_t c = 0; c < components_.size(); c++)
00793 {
00794 components_[c]->publish(dt);
00795 }
00796 }
00797 }
00798
00799 private:
00800 void joyCallback(const sensor_msgs::Joy::ConstPtr& msg)
00801 {
00802
00803 boost::mutex::scoped_lock lock(state_mutex_);
00804
00805 bool ok = true;
00806 for (size_t c = 0; c < components_.size(); c++)
00807 {
00808 if (ok)
00809 {
00810 ok &= !components_[c]->update(msg, state_msg_);
00811 }
00812 else
00813 {
00814
00815 components_[c]->stop();
00816 }
00817 }
00818 last_update_ = ros::Time::now();
00819 }
00820
00821 void stateCallback(const sensor_msgs::JointStateConstPtr& msg)
00822 {
00823
00824 boost::mutex::scoped_lock lock(state_mutex_);
00825
00826
00827 for (size_t msg_j = 0; msg_j < msg->name.size(); msg_j++)
00828 {
00829 size_t state_j;
00830 for (state_j = 0; state_j < state_msg_->name.size(); state_j++)
00831 {
00832 if (state_msg_->name[state_j] == msg->name[msg_j])
00833 {
00834 state_msg_->position[state_j] = msg->position[msg_j];
00835 state_msg_->velocity[state_j] = msg->velocity[msg_j];
00836 break;
00837 }
00838 }
00839 if (state_j == state_msg_->name.size())
00840 {
00841
00842 state_msg_->name.push_back(msg->name[msg_j]);
00843 state_msg_->position.push_back(msg->position[msg_j]);
00844 state_msg_->velocity.push_back(msg->velocity[msg_j]);
00845 }
00846 }
00847 }
00848
00849 std::vector<TeleopComponentPtr> components_;
00850 ros::Time last_update_;
00851 boost::mutex state_mutex_;
00852 sensor_msgs::JointStatePtr state_msg_;
00853 ros::Subscriber joy_sub_, state_sub_;
00854 };
00855
00856 int main(int argc, char** argv)
00857 {
00858 ros::init(argc, argv, "teleop");
00859 ros::NodeHandle n("~");
00860
00861 Teleop teleop;
00862 teleop.init(n);
00863
00864 ros::Rate r(30.0);
00865 while (ros::ok())
00866 {
00867 ros::spinOnce();
00868 teleop.publish(ros::Duration(1/30.0));
00869 r.sleep();
00870 }
00871
00872 return 0;
00873 }