37 #include <boost/thread/mutex.hpp> 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> 50 double integrate(
double desired,
double present,
double max_rate,
double dt)
52 if (desired > present)
53 return std::min(desired, present + max_rate * dt);
55 return std::max(desired, present - max_rate * dt);
67 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
68 const sensor_msgs::JointState::ConstPtr& state) = 0;
100 pnh.
param(
"button_deadman", deadman_, 10);
101 pnh.
param(
"axis_x", axis_x_, 3);
102 pnh.
param(
"axis_w", axis_w_, 0);
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);
112 pnh.
param(
"max_windup_time", max_windup_time, 0.25);
115 pnh.
param(
"use_mux", use_mux_,
true);
118 mux_ = nh.
serviceClient<topic_tools::MuxSelect>(
"/cmd_vel_mux/select");
121 cmd_vel_pub_ = nh.
advertise<geometry_msgs::Twist>(
"/teleop/cmd_vel", 1);
125 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
126 const sensor_msgs::JointState::ConstPtr& state)
128 bool deadman_pressed = joy->buttons[deadman_];
130 if (!deadman_pressed)
138 if (joy->axes[axis_x_] > 0.0)
139 desired_.linear.x = joy->axes[axis_x_] * max_vel_x_;
141 desired_.linear.x = joy->axes[axis_x_] * -min_vel_x_;
142 desired_.angular.z = joy->axes[axis_w_] * max_vel_w_;
153 boost::mutex::scoped_lock lock(odom_mutex_);
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);
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);
165 last_.angular.z = std::max(last_.angular.z, odom_.twist.twist.angular.z - max_acc_w_ * max_windup_time);
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_);
179 topic_tools::MuxSelect req;
180 req.request.topic = cmd_vel_pub_.getTopic();
183 prev_mux_topic_ = req.response.prev_topic;
197 last_ = desired_ = geometry_msgs::Twist();
198 cmd_vel_pub_.publish(last_);
202 topic_tools::MuxSelect req;
203 req.request.topic = prev_mux_topic_;
218 boost::mutex::scoped_lock lock(odom_mutex_);
260 pnh.
param(
"button_deadman", deadman_, 10);
261 pnh.
param(
"button_increase", inc_button_, 12);
262 pnh.
param(
"button_decrease", dec_button_, 14);
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);
271 pnh.
param(
"inhibit", inhibit_,
false);
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");
278 client_.reset(
new client_t(action_name,
true));
281 ROS_ERROR(
"%s may not be connected.", action_name.c_str());
286 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
287 const sensor_msgs::JointState::ConstPtr& state)
289 bool deadman_pressed = joy->buttons[deadman_];
291 if (!deadman_pressed)
295 for (
size_t i = 0; i < state->name.size(); i++)
297 if (state->name[i] == joint_name_)
299 actual_position_ = state->position[i];
306 if (joy->buttons[inc_button_])
308 desired_velocity_ = max_velocity_;
311 else if (joy->buttons[dec_button_])
313 desired_velocity_ = -max_velocity_;
318 desired_velocity_ = 0.0;
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));
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);
341 goal.trajectory.points.push_back(p);
343 client_->sendGoal(goal);
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;
355 last_velocity_ = 0.0;
382 pnh.
param(
"button_deadman", deadman_, 10);
383 pnh.
param(
"button_open", open_button_, 0);
384 pnh.
param(
"button_close", close_button_, 3);
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);
391 std::string action_name =
"gripper_controller/gripper_action";
392 client_.reset(
new client_t(action_name,
true));
395 ROS_ERROR(
"%s may not be connected.", action_name.c_str());
401 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
402 const sensor_msgs::JointState::ConstPtr& state)
404 bool deadman_pressed = joy->buttons[deadman_];
408 if (joy->buttons[open_button_])
410 else if (joy->buttons[close_button_])
422 control_msgs::GripperCommandGoal goal;
423 goal.command.position = max_position_;
424 goal.command.max_effort = max_effort_;
425 client_->sendGoal(goal);
430 control_msgs::GripperCommandGoal goal;
431 goal.command.position = min_position_;
432 goal.command.max_effort = max_effort_;
433 client_->sendGoal(goal);
459 pnh.
param(
"button_deadman", deadman_, 8);
460 pnh.
param(
"axis_pan", axis_pan_, 0);
461 pnh.
param(
"axis_tilt", axis_tilt_, 3);
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);
474 head_pan_joint_ =
"head_pan_joint";
475 head_tilt_joint_ =
"head_tilt_joint";
477 std::string action_name =
"head_controller/follow_joint_trajectory";
478 client_.reset(
new client_t(action_name,
true));
481 ROS_ERROR(
"%s may not be connected.", action_name.c_str());
486 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
487 const sensor_msgs::JointState::ConstPtr& state)
489 bool deadman_pressed = joy->buttons[deadman_];
491 if (!deadman_pressed)
495 for (
size_t i = 0; i < state->name.size(); i++)
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];
505 desired_pan_ = joy->axes[axis_pan_] * max_vel_pan_;
506 desired_tilt_ = joy->axes[axis_tilt_] * max_vel_tilt_;
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));
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);
535 goal.trajectory.points.push_back(p);
537 client_->sendGoal(goal);
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));
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;
553 last_pan_ = last_tilt_ = 0.0;
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);
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);
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);
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);
602 cmd_pub_ = nh.
advertise<geometry_msgs::TwistStamped>(
"/arm_controller/cartesian_twist/command", 10);
605 virtual bool update(
const sensor_msgs::Joy::ConstPtr& joy,
606 const sensor_msgs::JointState::ConstPtr& state)
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_];
612 if ((!(button_linear_pressed || button_angular_pressed) || !deadman_pressed) &&
621 if (button_linear_pressed)
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;
631 else if (button_angular_pressed)
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_;
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;
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());
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());
667 last_.header.frame_id =
"base_link";
669 cmd_pub_.publish(last_);
685 last_ = desired_ = geometry_msgs::TwistStamped();
686 cmd_pub_.publish(last_);
697 int axis_x_, axis_y_,
axis_z_, axis_roll_, axis_pitch_, axis_yaw_;
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);
737 TeleopComponentPtr
c;
744 components_.push_back(c);
751 components_.push_back(c);
758 components_.push_back(c);
764 components_.push_back(c);
772 components_.push_back(c);
775 state_msg_.reset(
new sensor_msgs::JointState());
785 for (
size_t c = 0;
c < components_.size();
c++)
787 components_[
c]->stop();
792 for (
size_t c = 0;
c < components_.size();
c++)
794 components_[
c]->publish(dt);
803 boost::mutex::scoped_lock lock(state_mutex_);
806 for (
size_t c = 0;
c < components_.size();
c++)
810 ok &= !components_[
c]->update(msg, state_msg_);
815 components_[
c]->stop();
824 boost::mutex::scoped_lock lock(state_mutex_);
827 for (
size_t msg_j = 0; msg_j < msg->name.size(); msg_j++)
830 for (state_j = 0; state_j < state_msg_->name.size(); state_j++)
832 if (state_msg_->name[state_j] == msg->name[msg_j])
834 state_msg_->position[state_j] = msg->position[msg_j];
835 state_msg_->velocity[state_j] = msg->velocity[msg_j];
839 if (state_j == state_msg_->name.size())
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]);
856 int main(
int argc,
char** argv)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void odomCallback(const nav_msgs::OdometryConstPtr &odom)
sensor_msgs::JointStatePtr state_msg_
boost::shared_ptr< client_t > client_
virtual void publish(const ros::Duration &dt)
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)
boost::shared_ptr< TeleopComponent > TeleopComponentPtr
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ArmTeleop(const std::string &name, ros::NodeHandle &nh)
std::string prev_mux_topic_
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
ros::Subscriber state_sub_
HeadTeleop(const std::string &name, ros::NodeHandle &nh)
virtual void publish(const ros::Duration &dt)
void joyCallback(const sensor_msgs::Joy::ConstPtr &msg)
boost::shared_ptr< client_t > client_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void init(ros::NodeHandle &nh)
geometry_msgs::TwistStamped last_
virtual void publish(const ros::Duration &dt)
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
virtual bool update(const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)=0
ros::Subscriber odom_sub_
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)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > client_t
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)
ROSCPP_DECL void spinOnce()
geometry_msgs::Twist last_
BaseTeleop(const std::string &name, ros::NodeHandle &nh)