marker_control.cpp
Go to the documentation of this file.
00001 /*
00002 * Copyright (c) 2011, Willow Garage, Inc.
00003 * All rights reserved.
00004 *
00005 * Redistribution and use in source and binary forms, with or without
00006 * modification, are permitted provided that the following conditions are met:
00007 *
00008 *     * Redistributions of source code must retain the above copyright
00009 *       notice, this list of conditions and the following disclaimer.
00010 *     * Redistributions in binary form must reproduce the above copyright
00011 *       notice, this list of conditions and the following disclaimer in the
00012 *       documentation and/or other materials provided with the distribution.
00013 *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014 *       contributors may be used to endorse or promote products derived from
00015 *       this software without specific prior written permission.
00016 *
00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 * POSSIBILITY OF SUCH DAMAGE.
00028 */
00029 
00030 // author: Adam Leeper
00031 
00032 // **** 10 ***** 20 ****** 30 ****** 40 ****** 50 ****** 60 ****** 70 ****** 80 ****** 90 ***** 100 ***** 110 ***** 120
00033 
00034 #include <ros/ros.h>
00035 #include <math.h>
00036 
00037 #include <arm_navigation_msgs/GetStateValidity.h>
00038 
00039 #include <interactive_markers/interactive_marker_server.h>
00040 #include <interactive_markers/menu_handler.h>
00041 
00042 #include <std_srvs/Empty.h>
00043 
00044 #include <actionlib/client/simple_action_client.h>
00045 #include <actionlib/server/simple_action_server.h>
00046    
00047 #include <boost/thread.hpp>
00048 
00049 #include <tf/transform_listener.h>
00050 
00051 #include <interactive_marker_helpers/interactive_marker_helpers.h>
00052 #include <pr2_object_manipulation_msgs/GetNavPoseAction.h>
00053 #include <pr2_marker_control/cloud_handler.h>
00054 #include <pr2_marker_control/marker_control.h>
00055 
00056 using namespace object_manipulator;
00057 using namespace visualization_msgs;
00058 using namespace interactive_markers;
00059 using namespace im_helpers;
00060 
00062 
00063 // First define a useful helper function...
00068 void offsetPS(tf::StampedTransform &st, const tf::Transform &offset)
00069 {
00070   tf::Transform pose = tf::Transform(st.getRotation(), st.getOrigin());
00071   pose = pose * offset;
00072   st.setData(pose);
00073 }
00074 
00076 geometry_msgs::PoseStamped PR2MarkerControl::toolToWrist(const geometry_msgs::PoseStamped &ps)
00077 {
00078   geometry_msgs::PoseStamped out;
00079   out.header = ps.header;
00080   tf::Transform T, P;
00081   tf::poseMsgToTF(ps.pose, P);
00082   tf::poseMsgToTF(tool_frame_offset_, T);
00083   tf::poseTFToMsg( P*T.inverse(), out.pose);
00084   //out.pose = object_manipulator::msg::applyShift(ps.pose, tf::Vector3(-0.15,0,0));
00085   return out;
00086 }
00087 
00089 geometry_msgs::PoseStamped PR2MarkerControl::wristToTool(const geometry_msgs::PoseStamped &ps)
00090 {
00091   geometry_msgs::PoseStamped out;
00092   out.header = ps.header;
00093   tf::Transform T, P;
00094   tf::poseMsgToTF(ps.pose, P);
00095   tf::poseMsgToTF(tool_frame_offset_, T);
00096   tf::poseTFToMsg( P*T, out.pose);
00097   //out.pose = object_manipulator::msg::applyShift(ps.pose, tf::Vector3(-0.15,0,0));
00098   return out;
00099 }
00100 
00101 // This is a convenience function (rather specific to this file) to get the arm name from one of several marker names.
00102 std::string getArmNameFromMarkerName(const std::string &name){
00103   std::string arm_name = "";
00104   if( name == "r_upper_arm_link" || name == "r_gripper_palm_link"
00105       || name == "r_gripper_l_finger_link" || name == "r_gripper_r_finger_link"
00106       || name == "r_gripper_l_finger_tip_link" || name == "r_gripper_r_finger_tip_link")
00107     arm_name = "right_arm";
00108   else if( name == "l_upper_arm_link" || name == "l_gripper_palm_link"
00109            || name == "l_gripper_l_finger_link" || name == "l_gripper_r_finger_link"
00110            || name == "l_gripper_l_finger_tip_link" || name == "l_gripper_r_finger_tip_link")
00111     arm_name = "left_arm";
00112   else
00113     ROS_WARN("Marker name [%s] not handled!", name.c_str());
00114 
00115   return arm_name;
00116 }
00117 
00119 
00120 
00121 PR2MarkerControl::PR2MarkerControl() :
00122   nh_("/"),
00123   pnh_("~"),
00124   server_("pr2_marker_control", "marker_control", false),
00125   tfl_(nh_),
00126   torso_client_(),
00127   base_client_(nh_, ros::Duration(2.0), &tfl_),
00128   tuck_arms_client_(nh_, ros::Duration(20.0)),
00129   check_state_validity_client_("/current_state_validator/get_state_validity"),
00130   collider_node_reset_srv_("/collider_node/reset"),
00131   snapshot_client_(&nh_, &tfl_, "interactive_manipulation_snapshot", 
00132                    "interactive_point_cloud", "interactive_manipulation_snapshot_server", 
00133                    mechanism_, "/odom_combined"),
00134   object_cloud_left_(&nh_, &tfl_, "in_hand_object_cloud_left", 
00135                      "in_hand_objects", "in_hand_object_server_left", 
00136                      mechanism_, "/l_wrist_roll_link"),
00137   object_cloud_right_(&nh_, &tfl_, "in_hand_object_cloud_right", 
00138                       "in_hand_objects", "in_hand_object_server_right", 
00139                       mechanism_, "/r_wrist_roll_link"),
00140   base_pose_client_("pr2_interactive_nav_action", true),
00141   gripper_pose_client_("pr2_interactive_gripper_pose_action", true),
00142   alignedOdomValid_(false),
00143   alignedOdomThread_( boost::bind( &PR2MarkerControl::publishAlignedOdom, this ) )
00144 {
00145   ROS_INFO( "-------------------------- Starting up PR2 MARKER CONTROL application. --------------------------------" );
00146 
00147   ros::Duration(2.0).sleep();
00148 
00149   pnh_.param<bool>("use_right_arm", use_right_arm_, true);
00150   pnh_.param<bool>("use_left_arm", use_left_arm_, true);
00151   pnh_.param<bool>("use_state_validator", use_state_validator_, true);
00152 
00153   pnh_.param<double>("gripper_control_linear_deadband",   gripper_control_linear_deadband_,  0.002);
00154   pnh_.param<double>("gripper_control_angular_deadband",  gripper_control_angular_deadband_, 0.01);
00155   pnh_.param<double>("update_period",  update_period_, 0.05);
00156   pnh_.param<double>("cartesian_clip_distance",  cartesian_clip_distance_, 2);
00157   pnh_.param<double>("cartesian_clip_angle",  cartesian_clip_angle_, 10);
00158   pnh_.param<std::string>("head_pointing_frame", head_pointing_frame_, "/default_head_pointing_frame");
00159   pnh_.param<std::string>("move_base_node_name", move_base_node_name_, "move_base_node");
00160   pnh_.param<bool>("nav_3d", using_3d_nav_, false);
00161 
00162   pnh_.param<double>("max_direct_nav_radius",   max_direct_nav_radius_,  0.4);
00163 
00164   nh_.param<int>("interactive_grasping/interface_number", interface_number_, 0);
00165   if (interface_number_) ROS_INFO("Using interface number %d for grasping study", interface_number_);
00166   nh_.param<int>("interactive_grasping/task_number", task_number_, 0);
00167   if (task_number_) ROS_INFO("Using task number %d for grasping study", task_number_);
00168 
00169   pnh_.param<bool>("planar_only", control_state_.planar_only_, false);
00170   pnh_.param<std::string>("marker_frame", manipulator_base_frame_, "base_link");
00171 
00172   pnh_.param<std::string>("l_gripper_type", l_gripper_type_, "pr2");
00173   pnh_.param<std::string>("r_gripper_type", r_gripper_type_, "pr2");
00174 
00175   object_cloud_left_sub_ = nh_.subscribe("/in_hand_object_left", 1, 
00176                                          &PR2MarkerControl::inHandObjectLeftCallback, this);
00177   object_cloud_right_sub_ = nh_.subscribe("/in_hand_object_right", 1, 
00178                                           &PR2MarkerControl::inHandObjectRightCallback, this);
00179 
00180   ROS_INFO("***************************** %s *****************************", manipulator_base_frame_.c_str());
00181 
00182   if (interface_number_ == 1)
00183   {
00184     control_state_.r_gripper_.on_ = true;
00185     control_state_.posture_r_ = true;
00186     switchToCartesian();
00187   }
00188 
00189   in_collision_r_ = false;
00190   in_collision_l_ = false;
00191 
00192   control_state_.r_gripper_.torso_frame_ = true;
00193   control_state_.l_gripper_.torso_frame_ = true;
00194   control_state_.dual_grippers_.torso_frame_ = true;
00195    
00196   tf::Transform offset = tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0, 0));
00197   pose_offset_.push_back(offset);
00198   pose_offset_.push_back(offset);
00199 
00200   dual_gripper_offsets_.push_back(offset);
00201   dual_gripper_offsets_.push_back(offset);
00202 
00203   dual_pose_offset_ = tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0));
00204 
00205   tool_frame_offset_ = msg::createPoseMsg(tf::Pose(tf::Quaternion::getIdentity(), tf::Vector3(0.18,0,0)));
00206 
00207   head_goal_pose_.pose.position.x = 1.0;
00208   head_goal_pose_.pose.position.z = 1.0;
00209   head_goal_pose_.header.frame_id = "base_link";
00210 
00211   base_goal_pose_.header.frame_id = "base_link";
00212   base_goal_pose_.pose.orientation.w = 1;
00213 
00214   // Must initialize the menus before creating the markers!
00215   initMenus();
00216 
00217   // Initialize (or hard "reset") of all markers.
00218   initAllMarkers();
00219 
00220   spin_timer_ =  nh_.createTimer(ros::Duration(update_period_), boost::bind( &PR2MarkerControl::fastUpdate, this ) );
00221   slow_sync_timer_ =  nh_.createTimer(ros::Duration(0.5), boost::bind( &PR2MarkerControl::slowUpdate, this ) );
00222 }
00223 
00224 
00225 void PR2MarkerControl::fastUpdate()
00226 {
00227   ros::Time now = ros::Time(0);
00228 
00229   tf::StampedTransform stamped;
00230   geometry_msgs::TransformStamped ts;
00231 
00232   if(control_state_.r_gripper_.on_)
00233   {
00234     geometry_msgs::PoseStamped ps;
00235     static geometry_msgs::PoseStamped last;
00236     tfl_.waitForTransform("r_wrist_roll_link", "base_link", now, ros::Duration(2.0));
00237     tfl_.lookupTransform("base_link", "r_wrist_roll_link", now, stamped);
00238     offsetPS(stamped, pose_offset_[0]);
00239     tf::transformStampedTFToMsg(stamped, ts);
00240     ps = object_manipulator::msg::createPoseStampedMsg(ts);
00241     ps.header.stamp = ros::Time(0);  // Time(0) makes this stay fixed in base_link
00242 
00243     double pos_dist = 0, angle = 0;
00244     mechanism_.poseDists(ps.pose, last.pose, pos_dist, angle);
00245     if(pos_dist > gripper_control_linear_deadband_ || angle > gripper_control_angular_deadband_)
00246     {
00247       server_.setPose("r_gripper_control", ps.pose, ps.header);
00248       last = ps;
00249     }
00250   }
00251   if(control_state_.l_gripper_.on_)
00252   {
00253     geometry_msgs::PoseStamped ps;
00254     static geometry_msgs::PoseStamped last;
00255     tfl_.waitForTransform("l_wrist_roll_link", manipulator_base_frame_, now, ros::Duration(2.0));
00256     tfl_.lookupTransform(manipulator_base_frame_, "l_wrist_roll_link", now, stamped);
00257     offsetPS(stamped, pose_offset_[1]);
00258     tf::transformStampedTFToMsg(stamped, ts);
00259     ps = object_manipulator::msg::createPoseStampedMsg(ts);
00260     ps.header.stamp = ros::Time(0); // Time(0) makes this stay fixed in base_link
00261 
00262     double pos_dist = 0, angle = 0;
00263     mechanism_.poseDists(ps.pose, last.pose, pos_dist, angle);
00264     if(pos_dist > gripper_control_linear_deadband_ || angle > gripper_control_angular_deadband_)
00265     {
00266       server_.setPose("l_gripper_control", ps.pose, ps.header);
00267       last = ps;
00268     }
00269   }
00270 
00271   server_.applyChanges();
00272 }
00273 
00274 void PR2MarkerControl::slowUpdate()
00275 {
00276   static bool last_r_cart, last_l_cart, last_move_base_active;
00277 
00278   bool r_cart = false, l_cart = false;
00279   bool init_mesh_markers = false, init_all_markers = false, init_control_markers = false;
00280 
00281 
00282   if(use_right_arm_)
00283   {
00284     r_cart = mechanism_.checkController("r_cart");
00285     if(! r_cart)
00286     {
00287       control_state_.r_gripper_.on_ = false;
00288       control_state_.posture_r_ = false;
00289       control_state_.dual_grippers_.on_ = false;
00290     }
00291     // It's much smoother if we don't do this!
00292     //if( r_cart && !control_state_.posture_r_ ) refreshPosture("right_arm");
00293     //if( r_cart ) refreshPosture("right_arm");
00294   }
00295   if(use_left_arm_)
00296   {
00297     l_cart = mechanism_.checkController("l_cart");
00298     if(! l_cart)
00299     {
00300       control_state_.l_gripper_.on_ = false;
00301       control_state_.posture_l_ = false;
00302       control_state_.dual_grippers_.on_ = false;
00303     }
00304     // It's much smoother if we don't do this!
00305     //if( l_cart && !control_state_.posture_l_ ) refreshPosture("left_arm");
00306     //if( l_cart ) refreshPosture("left_arm");
00307   }
00308 
00309 //  if( r_cart || l_cart )
00310 //  {
00311 //    if(joint_handle_)       menu_arms_.setCheckState(joint_handle_, MenuHandler::UNCHECKED);
00312 //    if(jtranspose_handle_)  menu_arms_.setCheckState(jtranspose_handle_, MenuHandler::CHECKED);
00313 //  }
00314 //  else
00315 //  {
00316 //    if(joint_handle_)       menu_arms_.setCheckState(joint_handle_, MenuHandler::CHECKED);
00317 //    if(jtranspose_handle_)  menu_arms_.setCheckState(jtranspose_handle_, MenuHandler::UNCHECKED);
00318 //    control_state_.r_gripper_.on_ = false;
00319 //    control_state_.l_gripper_.on_ = false;
00320 //    control_state_.posture_r_ = false;
00321 //    control_state_.posture_l_ = false;
00322 //  }
00323 
00324   bool controller_changed = (r_cart != last_r_cart) || (l_cart != last_l_cart);
00325   last_r_cart = r_cart;
00326   last_l_cart = l_cart;
00327 
00328   if(controller_changed)
00329   {
00330     //if(tuck_handle_) menu_arms_.setVisible(tuck_handle_, !(r_cart || l_cart) );
00331     //init_mesh_markers = true;
00332     //init_control_markers = true;
00333     init_all_markers = true;
00334     //initAllMarkers();
00335   }
00336 
00337   ROS_DEBUG("r_cart: %d  l_cart: %d", r_cart, l_cart);
00338 
00339   // ---------------------------------------------------------------
00340   // Current state validator stuff
00341 
00342   bool meshes_changed = false;
00343 
00344   bool in_collision_r = !checkStateValidity("right_arm");
00345   if (in_collision_r_ != in_collision_r) meshes_changed = true;
00346   in_collision_r_ = in_collision_r;
00347 
00348   bool in_collision_l = !checkStateValidity("left_arm");
00349   if (in_collision_l_ != in_collision_l) meshes_changed = true;
00350   in_collision_l_ = in_collision_l;
00351 
00352   init_mesh_markers = meshes_changed;
00353   //if (meshes_changed) initMeshMarkers();
00354 
00355   // ---------------------------------------------------------------
00356   // Base client stuff
00357   bool move_base_active = base_client_.hasGoal();
00358   if( move_base_active != last_move_base_active ) init_control_markers = true;
00359   last_move_base_active = move_base_active;
00360 
00361 
00362   // ---------------------------------------------------------------
00363   // Call a re-draw to the necessary markers.
00364   if(init_all_markers) initAllMarkers();
00365   else
00366   {
00367     if(init_control_markers) initControlMarkers();
00368     if(init_mesh_markers) initMeshMarkers();
00369   }
00370 }
00371 
00373 double PR2MarkerControl::getJointPosition( std::string name, const arm_navigation_msgs::RobotState& robot_state)
00374 {
00375   for (size_t i=0; i<robot_state.joint_state.name.size(); i++)
00376   {
00377     if (robot_state.joint_state.name[i] == name)
00378     {
00379       ROS_ASSERT(robot_state.joint_state.position.size() > i);
00380       return robot_state.joint_state.position[i];
00381     }
00382   }
00383   ROS_ERROR_STREAM("Joint " << name << " not found in robot state");
00384   return 0.0;
00385 }
00386 
00388 void PR2MarkerControl::initControlMarkers()
00389 {
00390   ros::Time now = ros::Time::now();
00391   ROS_INFO("Re-initializing all control markers!");
00392   arm_navigation_msgs::RobotState robot_state;
00393   //wait for the service to initialize, for how long it takes
00394   mechanism_.get_robot_state_client_.client(ros::Duration(-1));
00395   mechanism_.getRobotState(robot_state);
00396 
00397   
00398   control_state_.print();
00399   // Right gripper control
00400   if(!control_state_.dual_grippers_.on_ && control_state_.r_gripper_.on_ && use_right_arm_ &&
00401      (interface_number_ == 0 || interface_number_ == 1) )
00402   {
00403     tfl_.waitForTransform("r_wrist_roll_link","base_link", now, ros::Duration(2.0));
00404     tf::StampedTransform stamped;
00405     geometry_msgs::TransformStamped ts;
00406     geometry_msgs::PoseStamped ps;
00407     tfl_.lookupTransform("base_link", "r_wrist_roll_link", now, stamped);
00408     offsetPS(stamped, pose_offset_[0]);
00409     tf::transformStampedTFToMsg(stamped, ts);
00410     ps = msg::createPoseStampedMsg(ts);
00411     ps.header.stamp = ros::Time(0);   // Time(0) is needed, else the markers seem to end up in random places
00412     if ( control_state_.planar_only_ ) {
00413       ROS_INFO("making planar control");
00414       server_.insert(makePlanarMarker( "r_gripper_control", ps, 0.25, true), 
00415                      boost::bind( &PR2MarkerControl::updateGripper, this, _1, 0));
00416     } else {
00417       server_.insert(make6DofMarker( "r_gripper_control", ps, 0.25, control_state_.r_gripper_.torso_frame_,
00418                                      control_state_.r_gripper_.view_facing_),
00419                      boost::bind( &PR2MarkerControl::updateGripper, this, _1, 0));
00420     }
00421     menu_grippers_.apply(server_, "r_gripper_control");
00422   }
00423   else
00424   {
00425     server_.erase("r_gripper_control");
00426   }
00427 
00428   // Left gripper control
00429   if(!control_state_.dual_grippers_.on_ && control_state_.l_gripper_.on_ && use_left_arm_ &&
00430      (interface_number_ == 0 || interface_number_ == 1))
00431   {
00432     tfl_.waitForTransform("base_link", "odom_combined", now, ros::Duration(2.0));
00433     tf::StampedTransform tfbaseLink_expressedIn_odomCombined;
00434     tfl_.lookupTransform("odom_combined", "base_link", now, tfbaseLink_expressedIn_odomCombined);
00435     tf::Transform odomCombined2_expressedIn_odomCombined = tf::Transform(tfbaseLink_expressedIn_odomCombined.getRotation());
00436     tf::StampedTransform outST(odomCombined2_expressedIn_odomCombined, now, "odom_combined", "base_aligned_odom_combined"); 
00437     {
00438       boost::mutex::scoped_lock lock(alignedOdomMutex_);
00439       alignedOdom_ = outST;
00440       alignedOdomValid_ = true;
00441       tfb_.sendTransform(alignedOdom_);
00442       tfl_.setTransform(alignedOdom_);
00443     }
00444     
00445     /*
00446     tfl_.waitForTransform("l_wrist_roll_link", manipulator_base_frame_, now, ros::Duration(2.0));
00447     tfl_.waitForTransform("base_link", manipulator_base_frame_, now, ros::Duration(2.0));
00448     tf::StampedTransform tfbaseLink_expressedIn_odomCombined, tfgripper_expressedIn_odomCombined;
00449     tfl_.lookupTransform(manipulator_base_frame_, "l_wrist_roll_link", now, tfgripper_expressedIn_odomCombined);
00450     tfl_.lookupTransform(manipulator_base_frame_, "base_link", now, tfbaseLink_expressedIn_odomCombined);
00451     tf::Transform gripper_expressedIn_odomCombined = tf::Transform(tfgripper_expressedIn_odomCombined.getRotation(), tfgripper_expressedIn_odomCombined.getOrigin());
00452     tf::Transform odomCombined2_expressedIn_odomCombined = tf::Transform(tfbaseLink_expressedIn_odomCombined.getRotation());
00453     tf::Transform gripper_expressedIn_odomCombined2 = gripper_expressedIn_odomCombined * odomCombined2_expressedIn_odomCombined.inverse();
00454     
00455     geometry_msgs::PoseStamped psGripper_expressedIn_odomCombined2;
00456     tf::poseTFToMsg(gripper_expressedIn_odomCombined2, psGripper_expressedIn_odomCombined2.pose);
00457     psGripper_expressedIn_odomCombined2.header.stamp = ros::Time(0);
00458     
00459     server_.insert(make6DofMarker( "l_gripper_control", psGripper_expressedIn_odomCombined2, 
00460                                    0.25, control_state_.l_gripper_.torso_frame_,
00461                                    control_state_.l_gripper_.view_facing_),
00462                    boost::bind( &PR2MarkerControl::updateGripper, this, _1, 1 ));
00463     menu_grippers_.apply(server_, "l_gripper_control");
00464     */
00465     
00466     
00467     tfl_.waitForTransform("l_wrist_roll_link", manipulator_base_frame_, now, ros::Duration(2.0));
00468     tf::StampedTransform stamped;
00469     geometry_msgs::TransformStamped ts;
00470     geometry_msgs::PoseStamped ps;
00471     tfl_.lookupTransform(manipulator_base_frame_, "l_wrist_roll_link", now, stamped);
00472     offsetPS(stamped, pose_offset_[1]);
00473     tf::transformStampedTFToMsg(stamped, ts);
00474     ps = msg::createPoseStampedMsg(ts);
00475     ps.header.stamp = ros::Time(0); // Time(0) is needed, else the markers seem to end up in random places
00476     server_.insert(make6DofMarker( "l_gripper_control", ps, 0.25, control_state_.l_gripper_.torso_frame_,
00477                                    control_state_.l_gripper_.view_facing_),
00478                    boost::bind( &PR2MarkerControl::updateGripper, this, _1, 1 ));
00479     menu_grippers_.apply(server_, "l_gripper_control");
00480     
00481     ROS_DEBUG_STREAM("init marker in frame " << ps.header.frame_id << "(" 
00482                     << ps.pose.position.x << ", " 
00483                     << ps.pose.position.y << ", " 
00484                     << ps.pose.position.z << ")" );
00485  
00486   }
00487   else
00488   {
00489     server_.erase("l_gripper_control");
00490   }
00491 
00492   // Dual-gripper control
00493   if(control_state_.dual_grippers_.on_)
00494   {
00495 //    // TODO should this update with gripper poses, or be more of a fixed thing?
00496 //    // If it auto updates it might lead to stability issues...
00497 //    tfl_.waitForTransform("r_gripper_tool_frame","base_link", now, ros::Duration(2.0));
00498 //    tfl_.waitForTransform("l_gripper_tool_frame","base_link", now, ros::Duration(2.0));
00499 //    tf::StampedTransform stamped;
00500 //    geometry_msgs::TransformStamped ts;
00501 //    geometry_msgs::PoseStamped ps;
00502 //    tfl_.lookupTransform("base_link", "r_wrist_roll_link", now, stamped);
00503 //    offsetPS(stamped, pose_offset_[1]);
00504 //    tf::transformStampedTFToMsg(stamped, ts);
00505 //    ps = msg::createPoseStampedMsg(ts);
00506 
00507     tf::Transform dual_grippers_frame_tf;
00508     tf::poseMsgToTF(dual_grippers_frame_.pose, dual_grippers_frame_tf);
00509     tf::Transform offset_frame = dual_grippers_frame_tf * dual_pose_offset_.inverse();
00510     geometry_msgs::Pose offset_pose;
00511     tf::poseTFToMsg(offset_frame, offset_pose);
00512     geometry_msgs::PoseStamped offset_ps = object_manipulator::msg::createPoseStampedMsg(offset_pose,
00513                                                                                   dual_grippers_frame_.header.frame_id,
00514                                                                                   ros::Time(0));
00515     server_.insert(make6DofMarker( "dual_gripper_control", offset_ps, 0.25, 
00516                                    control_state_.dual_grippers_.torso_frame_, false),
00517                    boost::bind( &PR2MarkerControl::updateDualGripper, this, _1 ));
00518     menu_dual_grippers_.apply(server_, "dual_gripper_control");
00519   }
00520   else
00521   {
00522     server_.erase("dual_gripper_control");
00523   }
00524 
00525 
00526   if(control_state_.posture_r_ && use_right_arm_ &&
00527      (interface_number_ <= 2))
00528   {
00529       tf::StampedTransform stamped;
00530       geometry_msgs::TransformStamped ts;
00531       geometry_msgs::PoseStamped ps;
00532       tfl_.waitForTransform("r_shoulder_pan_link","base_link", now, ros::Duration(2.0));
00533       tfl_.lookupTransform("base_link", "r_shoulder_pan_link", now, stamped);
00534       tf::transformStampedTFToMsg(stamped, ts);
00535       float angle = getJointPosition("r_upper_arm_roll_joint", robot_state);
00536       ts.transform.rotation = msg::createQuaternionMsg( tf::Quaternion( tf::Vector3(1,0,0), angle) );
00537       ps = msg::createPoseStampedMsg(ts);
00538       ps.header.stamp = ros::Time(0);
00539       server_.insert(makePostureMarker( "r_posture_control", ps, 0.55, false, false),
00540                  boost::bind( &PR2MarkerControl::updatePosture, this, _1, 0 ));
00541   }
00542   else
00543   {
00544       server_.erase("r_posture_control");
00545   }
00546 
00547   if(control_state_.posture_l_ && use_left_arm_ &&
00548      (interface_number_ <= 2))
00549   {
00550       tf::StampedTransform stamped;
00551       geometry_msgs::TransformStamped ts;
00552       geometry_msgs::PoseStamped ps;
00553       tfl_.waitForTransform("l_shoulder_pan_link",manipulator_base_frame_, now, ros::Duration(2.0));
00554       tfl_.lookupTransform(manipulator_base_frame_, "l_shoulder_pan_link", now, stamped);
00555       tf::transformStampedTFToMsg(stamped, ts);
00556       float angle = getJointPosition("l_upper_arm_roll_joint", robot_state);
00557       ts.transform.rotation = msg::createQuaternionMsg( tf::Quaternion( tf::Vector3(1,0,0), angle) );
00558       ps = msg::createPoseStampedMsg(ts);
00559       ps.header.stamp = ros::Time(0);
00560       server_.insert(makePostureMarker( "l_posture_control", ps, 0.55, false, false),
00561                  boost::bind( &PR2MarkerControl::updatePosture, this, _1, 1 ));
00562   }
00563   else
00564   {
00565     server_.erase("l_posture_control");
00566   }
00567 
00568   if(control_state_.head_on_ && control_state_.init_head_goal_)
00569   {
00570     control_state_.init_head_goal_ = false;
00571     //geometry_msgs::PoseStamped ps = msg::createPoseStampedMsg( head_goal_pose_, "base_link", now);
00572     head_goal_pose_.header.stamp = ros::Time(0);
00573     //ps.header.stamp = ros::Time(0);
00574     server_.insert(makeHeadGoalMarker( "head_point_goal", head_goal_pose_, 0.1),
00575                    boost::bind( &PR2MarkerControl::updateHeadGoal, this, _1, 0 ));
00576   }
00577   if(!control_state_.head_on_)
00578   {
00579     server_.erase("head_point_goal");
00580   }
00581 
00582   if (interface_number_ == 0)
00583   {
00584     geometry_msgs::PoseStamped ps;
00585     ps.pose.position.x = -0.35;
00586     ps.pose.position.z = 1.1;
00587     ps.pose.orientation.w = 1;
00588     ps.header.frame_id = "base_link";
00589     ps.header.stamp = ros::Time(0);
00590     server_.insert(makeElevatorMarker( "torso_control", ps, 0.25, false),
00591                    boost::bind( &PR2MarkerControl::updateTorso, this, _1 ));
00592     menu_torso_.apply(server_, "torso_control");
00593   }
00594 
00595   if(control_state_.base_on_ && interface_number_ == 0) // base control (!)
00596   {
00597     geometry_msgs::PoseStamped ps;
00598     ps.pose.orientation.w = 1;
00599     ps.header.frame_id = "base_link";
00600     ps.header.stamp = ros::Time(0);
00601     server_.insert(makeBaseMarker( "base_control", ps, 0.75, false),
00602                    boost::bind( &PR2MarkerControl::updateBase, this, _1 ));
00603   }
00604   else
00605   {
00606     server_.erase("base_control");
00607   }
00608 
00609   // The giant ball around the robot when it is driving somewhere.
00610   if( base_client_.hasGoal() )
00611   {
00612     geometry_msgs::PoseStamped ps;
00613     ps.pose.position.z = 1.0;
00614     ps.pose.orientation.w = 1;
00615     ps.header.frame_id = "base_link";
00616     ps.header.stamp = ros::Time(0);
00617 
00618     std_msgs::ColorRGBA color = object_manipulator::msg::createColorMsg(1.0, 0.8, 0.8, 0.2);
00619     server_.insert(makeButtonSphere( "move_base_e_stop", ps, 2.0, false, false, color ));
00620     server_.setCallback("move_base_e_stop", boost::bind( &PR2MarkerControl::cancelBaseMovement, this),
00621                           visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN );
00622   
00623     // TODO this should absolutely be read from the robot_description parameter
00624     std::vector< std::string > mesh_paths, mesh_frames;
00625     mesh_paths.push_back("package://pr2_description/meshes/base_v0/base.dae");
00626     mesh_frames.push_back("base_link");
00627     mesh_paths.push_back("package://pr2_description/meshes/torso_v0/torso_lift.dae");
00628     mesh_frames.push_back("torso_lift_link");
00629     mesh_paths.push_back("package://pr2_description/meshes/shoulder_v0/shoulder_pan.dae");
00630     mesh_frames.push_back("r_shoulder_pan_link");
00631     mesh_paths.push_back("package://pr2_description/meshes/shoulder_v0/shoulder_pan.dae");
00632     mesh_frames.push_back("l_shoulder_pan_link");
00633     mesh_paths.push_back("package://pr2_description/meshes/shoulder_v0/shoulder_lift.dae");
00634     mesh_frames.push_back("r_shoulder_lift_link");
00635     mesh_paths.push_back("package://pr2_description/meshes/shoulder_v0/shoulder_lift.dae");
00636     mesh_frames.push_back("l_shoulder_lift_link");
00637     mesh_paths.push_back("package://pr2_description/meshes/upper_arm_v0/upper_arm.dae");
00638     mesh_frames.push_back("r_upper_arm_link");
00639     mesh_paths.push_back("package://pr2_description/meshes/upper_arm_v0/upper_arm.dae");
00640     mesh_frames.push_back("l_upper_arm_link");
00641     mesh_paths.push_back("package://pr2_description/meshes/forearm_v0/forearm.dae");
00642     mesh_frames.push_back("r_forearm_link");
00643     mesh_paths.push_back("package://pr2_description/meshes/forearm_v0/forearm.dae");
00644     mesh_frames.push_back("l_forearm_link");
00645 
00646     // Right Gripper
00647     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/gripper_palm.dae");
00648     mesh_frames.push_back("r_gripper_palm_link");
00649     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/upper_finger_r.stl");
00650     mesh_frames.push_back("r_gripper_r_finger_link");
00651     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/upper_finger_l.stl");
00652     mesh_frames.push_back("r_gripper_l_finger_link");
00653     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/finger_tip_r.stl");
00654     mesh_frames.push_back("r_gripper_r_finger_tip_link");
00655     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/finger_tip_l.stl");
00656     mesh_frames.push_back("r_gripper_l_finger_tip_link");
00657 
00658 
00659     // Left Gripper
00660     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/gripper_palm.dae");
00661     mesh_frames.push_back("l_gripper_palm_link");
00662     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/upper_finger_r.stl");
00663     mesh_frames.push_back("l_gripper_r_finger_link");
00664     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/upper_finger_l.stl");
00665     mesh_frames.push_back("l_gripper_l_finger_link");
00666     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/finger_tip_r.stl");
00667     mesh_frames.push_back("l_gripper_r_finger_tip_link");
00668     mesh_paths.push_back("package://pr2_description/meshes/gripper_v0/finger_tip_l.stl");
00669     mesh_frames.push_back("l_gripper_l_finger_tip_link");
00670 
00671     // Head
00672     mesh_paths.push_back("package://pr2_description/meshes/head_v0/head_pan.dae");
00673     mesh_frames.push_back("head_pan_link");
00674     mesh_paths.push_back("package://pr2_description/meshes/head_v0/head_tilt.dae");
00675     mesh_frames.push_back("head_tilt_link");
00676 
00677 
00678     if(mesh_paths.size() != mesh_frames.size()) ROS_ERROR("The number of mesh paths and mash frame_ids is not equal!");
00679 
00680     std::vector< geometry_msgs::PoseStamped > mesh_poses;
00681     for(size_t i = 0; i < mesh_paths.size(); i++)
00682     {
00683         geometry_msgs::PoseStamped ps;
00684         ps.header.stamp = ros::Time(0);
00685         ps.header.frame_id = mesh_frames[i];
00686         ps.pose.orientation.w = 1;
00687         tfl_.waitForTransform("base_link", ps.header.frame_id, ps.header.stamp,ros::Duration(3.0));
00688         tfl_.transformPose("base_link", ps, ps);
00689         mesh_poses.push_back(ps);
00690     }
00691 
00692     server_.insert(makePosedMultiMeshMarker( "move_base_goal", base_goal_pose_, mesh_poses, mesh_paths, 1.0, true));
00693 
00694   }
00695   else
00696   {
00697     server_.erase("move_base_e_stop");
00698     server_.erase("move_base_goal");
00699   }
00700 
00701 }
00702 
00704 void PR2MarkerControl::initMeshMarkers()
00705 {
00706   ros::Time now = ros::Time(0);
00707 
00708   // For making the interactive marker meshes slightly bigger than the default robot_model meshes
00709   double scale_factor = 1.02;
00710   double mesh_offset  = -0.002;
00711   //double palm_scale_factor = 1.15;
00712   //double palm_mesh_offset  = -0.017;
00713   geometry_msgs::Quaternion q_identity;
00714   geometry_msgs::Quaternion q_rotateX180;
00715   q_rotateX180.w = 0;
00716   q_rotateX180.x = 1;
00717 
00718   // All interactive markers will be set to time(0), so they update automatically in rviz.
00719   geometry_msgs::PoseStamped ps;
00720   ps.header.stamp = ros::Time(0);
00721 
00722   if (true) // Head is always on
00723   {
00724     ps.header.frame_id = "/head_tilt_link";
00725     server_.insert(makeMeshMarker( "head_tilt_link", "package://pr2_description/meshes/head_v0/head_tilt.dae",
00726                                    ps, scale_factor));
00727     menu_head_.apply(server_, "head_tilt_link");
00728   }
00729 
00730   // Choose correct gripper geometry. This will change when we fix all this to read in urdf
00731   std::string l_gripper_palm_path, l_gripper_finger_path, l_gripper_fingertip_path;
00732   if (l_gripper_type_ == "lcg")
00733   {
00734     l_gripper_palm_path = "package://gripper_control/meshes/lcg_actuator_palm_mesh_v1-55.STL";
00735     l_gripper_finger_path = "package://gripper_control/meshes/lcg_proximal_mesh_v1-55.STL";
00736     l_gripper_fingertip_path = "package://gripper_control/meshes/lcg_distal_mesh_v1-55.STL";
00737   }
00738   else
00739   {
00740     if (l_gripper_type_ != "pr2") ROS_WARN("Unrecognized gripper type in marker control; defaulting to PR2 gripper");
00741     l_gripper_palm_path = "package://pr2_description/meshes/gripper_v0/gripper_palm.dae";
00742     l_gripper_finger_path = "package://pr2_description/meshes/gripper_v0/l_finger.dae";
00743     l_gripper_fingertip_path = "package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
00744   }
00745   std::string r_gripper_palm_path, r_gripper_finger_path, r_gripper_fingertip_path;
00746   if (r_gripper_type_ == "lcg")
00747   {
00748     r_gripper_palm_path = "package://gripper_control/meshes/lcg_actuator_palm_mesh_v1-55.STL";
00749     r_gripper_finger_path = "package://gripper_control/meshes/lcg_proximal_mesh_v1-55.STL";
00750     r_gripper_fingertip_path = "package://gripper_control/meshes/lcg_distal_mesh_v1-55.STL";
00751   }
00752   else
00753   {
00754     if (r_gripper_type_ != "pr2") ROS_WARN("Unrecognized gripper type in marker control; defaulting to PR2 gripper");
00755     r_gripper_palm_path = "package://pr2_description/meshes/gripper_v0/gripper_palm.dae";
00756     r_gripper_finger_path = "package://pr2_description/meshes/gripper_v0/l_finger.dae";
00757     r_gripper_fingertip_path = "package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
00758   }
00759 
00760   if(use_right_arm_)
00761   {
00762     ps.pose = geometry_msgs::Pose();
00763     ps.header.frame_id = "/r_upper_arm_link";
00764     ps.pose.position.x = mesh_offset*2;
00765     server_.insert(makeMeshMarker( "r_upper_arm_link", "package://pr2_description/meshes/upper_arm_v0/upper_arm.dae",
00766                                    ps, scale_factor, object_manipulator::msg::createColorMsg(1, 0 , 0, 1),
00767                                    in_collision_r_));
00768     server_.setCallback("r_upper_arm_link", boost::bind( &PR2MarkerControl::upperArmButtonCB, this, _1, 0),
00769                         visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK );
00770     menu_arms_.apply(server_, "r_upper_arm_link");
00771 
00772     // --------------------------------------------------------
00773     ps.header.frame_id = "/r_gripper_palm_link";
00774     if (r_gripper_type_ == "pr2") ps.pose.position.x = mesh_offset;
00775     else ps.pose.position.x = 0.0;
00776     ps.pose.orientation = q_identity;
00777     server_.insert(makeMeshMarker( "r_gripper_palm_link", r_gripper_palm_path, ps, scale_factor),
00778                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00779                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00780     menu_gripper_close_.apply(server_, "r_gripper_palm_link");
00781 
00782     ps.header.frame_id = "/r_gripper_l_finger_link";
00783     ps.pose.position.x = mesh_offset/2;
00784     ps.pose.orientation = q_identity;
00785     server_.insert(makeMeshMarker( "r_gripper_l_finger_link", r_gripper_finger_path, ps, scale_factor),
00786                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00787                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00788     menu_gripper_close_.apply(server_, "r_gripper_l_finger_link");
00789 
00790     ps.header.frame_id = "/r_gripper_l_finger_tip_link";
00791     ps.pose.position.x = mesh_offset/4;
00792     ps.pose.orientation = q_identity;
00793     server_.insert(makeMeshMarker( "r_gripper_l_finger_tip_link", r_gripper_fingertip_path, ps, scale_factor*1.02),
00794                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00795                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00796     menu_gripper_close_.apply(server_, "r_gripper_l_finger_tip_link");
00797 
00798     ps.header.frame_id = "/r_gripper_r_finger_link";
00799     ps.pose.position.x = mesh_offset/2;
00800     if (r_gripper_type_ == "pr2") ps.pose.orientation = q_rotateX180;
00801     else ps.pose.orientation = q_identity;
00802     server_.insert(makeMeshMarker( "r_gripper_r_finger_link", r_gripper_finger_path, ps, scale_factor),
00803                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00804                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00805     menu_gripper_close_.apply(server_, "r_gripper_r_finger_link");
00806 
00807     ps.header.frame_id = "/r_gripper_r_finger_tip_link";
00808     ps.pose.position.x = mesh_offset/4;
00809     if (r_gripper_type_ == "pr2") ps.pose.orientation = q_rotateX180;
00810     else ps.pose.orientation = q_identity;
00811     server_.insert(makeMeshMarker( "r_gripper_r_finger_tip_link", r_gripper_fingertip_path, ps, scale_factor*1.02),
00812                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00813                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00814     menu_gripper_close_.apply(server_, "r_gripper_r_finger_tip_link");
00815 
00816     // Try to clean up
00817     ps.pose.orientation = q_identity;
00818   }
00819 
00820   if(use_left_arm_)
00821   {
00822     ps.pose = geometry_msgs::Pose();
00823     ps.header.frame_id = "/l_upper_arm_link";
00824     ps.pose.position.x = mesh_offset*2;
00825     server_.insert(makeMeshMarker( "l_upper_arm_link", "package://pr2_description/meshes/upper_arm_v0/upper_arm.dae",
00826                                    ps, scale_factor, object_manipulator::msg::createColorMsg(1, 0 , 0, 1),
00827                                    in_collision_l_));
00828     server_.setCallback("l_upper_arm_link", boost::bind( &PR2MarkerControl::upperArmButtonCB, this, _1, 1),
00829                         visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK );
00830     menu_arms_.apply(server_, "l_upper_arm_link");
00831 
00832     // --------------------------------------------------------
00833     ps.header.frame_id = "/l_gripper_palm_link";
00834     if (l_gripper_type_ == "pr2") ps.pose.position.x = mesh_offset;
00835     else ps.pose.position.x = 0.0;
00836     ps.pose.orientation = q_identity;
00837     server_.insert(makeMeshMarker( "l_gripper_palm_link", l_gripper_palm_path, ps, scale_factor),
00838                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00839                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00840     menu_gripper_close_.apply(server_, "l_gripper_palm_link");
00841 
00842     ps.header.frame_id = "/l_gripper_l_finger_link";
00843     ps.pose.position.x = mesh_offset/2;
00844     ps.pose.orientation = q_identity;
00845     server_.insert(makeMeshMarker( "l_gripper_l_finger_link", l_gripper_finger_path, ps, scale_factor),
00846                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00847                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00848     menu_gripper_close_.apply(server_, "l_gripper_l_finger_link");
00849 
00850     ps.header.frame_id = "/l_gripper_l_finger_tip_link";
00851     ps.pose.position.x = mesh_offset/4;
00852     ps.pose.orientation = q_identity;
00853     server_.insert(makeMeshMarker( "l_gripper_l_finger_tip_link", l_gripper_fingertip_path, ps, scale_factor*1.02),
00854                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00855                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00856     menu_gripper_close_.apply(server_, "l_gripper_l_finger_tip_link");
00857 
00858     ps.header.frame_id = "/l_gripper_r_finger_link";
00859     ps.pose.position.x = mesh_offset/2;
00860     if (l_gripper_type_ == "pr2") ps.pose.orientation = q_rotateX180;
00861     else ps.pose.orientation = q_identity;
00862     server_.insert(makeMeshMarker( "l_gripper_r_finger_link", l_gripper_finger_path, ps, scale_factor),
00863                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00864                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00865     menu_gripper_close_.apply(server_, "l_gripper_r_finger_link");
00866 
00867     ps.header.frame_id = "/l_gripper_r_finger_tip_link";
00868     ps.pose.position.x = mesh_offset/4;
00869     if (l_gripper_type_ == "pr2") ps.pose.orientation = q_rotateX180;
00870     else ps.pose.orientation = q_identity;
00871     server_.insert(makeMeshMarker( "l_gripper_r_finger_tip_link", l_gripper_fingertip_path, ps, scale_factor*1.02),
00872                    boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "toggle"), 
00873                    visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00874     menu_gripper_close_.apply(server_, "l_gripper_r_finger_tip_link");
00875 
00876     // Try to clean up
00877     ps.pose.orientation = q_identity;
00878   }
00879 
00880   if (interface_number_ == 0) // base link not allowed in studies
00881   {
00882     ps.pose = geometry_msgs::Pose();
00883     ps.header.frame_id = "base_link";
00884     ps.pose.position.x = 0.0;
00885     ps.pose.position.z = -0.01;
00886     server_.insert(makeMeshMarker( "base_link", "package://pr2_description/meshes/base_v0/base.dae",
00887                                    ps, scale_factor));
00888     server_.setCallback("base_link", boost::bind( &PR2MarkerControl::baseButtonCB, this, _1),
00889                         visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK );
00890     menu_base_.apply(server_, "base_link");
00891   }
00892 
00893   if(control_state_.projector_on_)
00894   {
00895     ps.pose = geometry_msgs::Pose();
00896     ps.header.frame_id = "/projector_wg6802418_frame";
00897     ps.pose.position.x = 0.07;
00898     ps.pose.position.z = 0.02;
00899     ps.pose.orientation = msg::createQuaternionMsg( tf::Quaternion(tf::Vector3(0,1,0), M_PI/2));
00900     ps.header.stamp = ros::Time(0);
00901     server_.insert(makeProjectorMarker( "projector_control", ps, 1.0),
00902                    boost::bind( &PR2MarkerControl::projectorMenuCB, this, _1 ));
00903   }
00904   else
00905   {
00906     server_.erase("projector_control");
00907   }
00908 
00909   // The "reset" box over the PR2's head.
00910   ps = msg::createPoseStampedMsg(msg::createPointMsg(0,0,0.85), msg::createQuaternionMsg(0,0,0,1),
00911                                  "/torso_lift_link", ros::Time(0));
00912   server_.insert(makeButtonBox( "PR2 Marker Control Reset", ps, 0.05, false, true),
00913                  boost::bind( &PR2MarkerControl::initAllMarkers, this, true ),
00914                  visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00915 }
00916 
00917 
00918 void PR2MarkerControl::switchToCartesian()
00919 {
00920   ROS_DEBUG("Switching to cartesian control.");
00921 
00922   // start out with posture control disabled
00923   std::vector<double> arm_angles(7);
00924   for( size_t i = 0; i < arm_angles.size(); i++) arm_angles[i] = 9999;
00925 
00926   mechanism_.get_robot_state_client_.client(ros::Duration(100.0));
00927   if(use_left_arm_){
00928       try {
00929         mechanism_.switchToCartesian("left_arm");
00930       }
00931       catch ( std::runtime_error &e )
00932       {
00933         ROS_ERROR("Caught exception while switching to cartesian controller: %s", e.what( ));
00934       }
00935       mechanism_.sendCartesianPostureCommand("left_arm", arm_angles);
00936   }
00937 
00938   if(use_right_arm_)
00939   {
00940       try {
00941         mechanism_.switchToCartesian("right_arm");
00942       }
00943       catch ( std::runtime_error &e ) {
00944         ROS_ERROR("Caught exception while switching to cartesian controller: %s", e.what( ));
00945       }
00946       mechanism_.sendCartesianPostureCommand("right_arm", arm_angles);
00947   }
00948 
00949   if(joint_handle_)       menu_arms_.setCheckState(joint_handle_, MenuHandler::UNCHECKED);
00950   if(jtranspose_handle_)  menu_arms_.setCheckState(jtranspose_handle_, MenuHandler::CHECKED);
00951 }
00952 
00953 void PR2MarkerControl::switchToJoint()
00954 {
00955   ROS_DEBUG("Switching to joint control.");
00956   if(use_left_arm_)
00957   {
00958       try {
00959         mechanism_.switchToJoint("left_arm");
00960       }
00961       catch ( std::runtime_error &e ) {
00962         ROS_ERROR("Caught exception while switching to cartesian controller: %s", e.what( ));
00963       }
00964   }
00965 
00966   if(use_right_arm_)
00967   {
00968       try {
00969         mechanism_.switchToJoint("right_arm");
00970       }
00971       catch ( std::runtime_error &e ) {
00972         ROS_ERROR("Caught exception while switching to cartesian controller: %s", e.what( ));
00973       }
00974   }
00975 
00976   if(joint_handle_)       menu_arms_.setCheckState(joint_handle_, MenuHandler::CHECKED);
00977   if(jtranspose_handle_)  menu_arms_.setCheckState(jtranspose_handle_, MenuHandler::UNCHECKED);
00978 }
00979 
00980 bool PR2MarkerControl::checkStateValidity(std::string arm_name)
00981 {
00982   // Hack to avoid using this for now
00983   if(!use_state_validator_) return true;
00984 
00985   if (interface_number_ != 0) return true;
00986   arm_navigation_msgs::GetStateValidity::Request request;
00987   request.group_name = arm_name;
00988   arm_navigation_msgs::GetStateValidity::Response response;
00989   try
00990   {
00991     if (!check_state_validity_client_.client().call(request, response))
00992     {
00993       ROS_ERROR("Call to get state validity failed");
00994       return false;
00995     }
00996     if (response.error_code.val != response.error_code.SUCCESS) return false;
00997     return true;
00998   }
00999   catch (object_manipulator::ServiceNotFoundException &ex)
01000   {
01001     ROS_ERROR("Get state validity service not found");
01002     return false;
01003   }
01004 }
01005 
01006 void PR2MarkerControl::updateHeadGoal( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id )
01007 {
01008   ros::Time now = ros::Time(0);
01009 
01010   switch ( feedback->event_type )
01011   {
01012     case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
01013       ROS_INFO_STREAM( feedback->marker_name << " was clicked on." );
01014       break;
01015     case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT:
01016       ROS_INFO_STREAM(    "Marker " << feedback->marker_name
01017                        << " control " << feedback->control_name
01018                        << " menu_entry_id " << feedback->menu_entry_id);
01019 
01020     case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
01021       geometry_msgs::PointStamped ps;
01022       ps.point = feedback-> pose.position;
01023       ps.header.frame_id = feedback->header.frame_id;
01024       ps.header.stamp = now;
01025       head_goal_pose_.pose = feedback->pose;
01026       head_goal_pose_.header = feedback->header;
01027       mechanism_.pointHeadAction(ps, head_pointing_frame_, false);
01028       break;
01029   }
01030 }
01031 
01032 void PR2MarkerControl::targetPointMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01033 {
01034   control_state_.head_on_ ^= true;
01035   control_state_.init_head_goal_ = true;
01036 
01037   if(control_state_.head_on_)
01038     menu_head_.setCheckState(head_target_handle_, MenuHandler::CHECKED);
01039   else
01040     menu_head_.setCheckState(head_target_handle_, MenuHandler::UNCHECKED);
01041 
01042   initControlMarkers();
01043 }
01044 
01045 void PR2MarkerControl::projectorMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01046 {
01047   if(control_state_.projector_on_)
01048   {
01049     ROS_INFO("Trying to turn projector OFF");
01050     int ok = system("rosrun dynamic_reconfigure dynparam set camera_synchronizer_node \"{'projector_mode':1, 'narrow_stereo_trig_mode':2}\" ");
01051     ROS_INFO("Done!");
01052     if(ok < 0)
01053       ROS_WARN("Dynamic reconfigure for setting trigger mode OFF failed");
01054     else
01055     {
01056       control_state_.projector_on_ = false;
01057       menu_head_.setCheckState(projector_handle_, MenuHandler::UNCHECKED);
01058     }
01059   }
01060   else
01061   {
01062     ROS_INFO("Trying to turn projector ON");
01063     int ok = system("rosrun dynamic_reconfigure dynparam set camera_synchronizer_node \"{'projector_mode':3, 'narrow_stereo_trig_mode':5}\" ");
01064     ROS_INFO("Done!");
01065     if(ok < 0)
01066       ROS_WARN("Dynamic reconfigure for setting trigger mode ON failed");
01067     else
01068     {
01069       control_state_.projector_on_ = true;
01070       menu_head_.setCheckState(projector_handle_, MenuHandler::CHECKED);
01071     }
01072   }
01073   //menu_head_.reApply(server_);
01074   initMeshMarkers();
01075 }
01076 
01077 void PR2MarkerControl::gripperToggleModeCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01078 {
01079   MenuHandler::EntryHandle handle = feedback->menu_entry_id;
01080   //MenuHandler::CheckState state;
01081   //if(!menu_arms_.getCheckState(handle, state))  return;
01082 
01083   if ( handle == gripper_view_facing_handle_ )
01084   {
01085     control_state_.r_gripper_.view_facing_ = true;
01086     control_state_.l_gripper_.view_facing_ = true;
01087     assert(menu_grippers_.setCheckState(gripper_view_facing_handle_, MenuHandler::CHECKED));
01088     assert(menu_grippers_.setCheckState(gripper_6dof_handle_, MenuHandler::UNCHECKED));
01089   }
01090   if ( handle == gripper_6dof_handle_ )
01091   {
01092     control_state_.r_gripper_.view_facing_ = false;
01093     control_state_.l_gripper_.view_facing_ = false;
01094     assert(menu_grippers_.setCheckState(gripper_view_facing_handle_, MenuHandler::UNCHECKED));
01095     assert(menu_grippers_.setCheckState(gripper_6dof_handle_, MenuHandler::CHECKED));
01096   }
01097 
01098   initControlMarkers();
01099 }
01100 
01101 void PR2MarkerControl::gripperToggleFixedCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01102 {
01103   control_state_.r_gripper_.torso_frame_ ^= true;
01104   control_state_.l_gripper_.torso_frame_ ^= true;
01105 
01106   // TODO right now I'm assuming these will always be in the same state together...
01107   if(control_state_.r_gripper_.torso_frame_)
01108     menu_grippers_.setCheckState(gripper_fixed_control_handle_, MenuHandler::CHECKED);
01109   else
01110     menu_grippers_.setCheckState(gripper_fixed_control_handle_, MenuHandler::UNCHECKED);
01111 
01112   initControlMarkers();
01113 }
01114 
01115 void PR2MarkerControl::dualGripperToggleFixedCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01116 {
01117   control_state_.dual_grippers_.torso_frame_ ^= true;
01118 
01119   if(control_state_.dual_grippers_.torso_frame_)
01120     menu_dual_grippers_.setCheckState(dual_gripper_fixed_control_handle_, MenuHandler::CHECKED);
01121   else
01122     menu_dual_grippers_.setCheckState(dual_gripper_fixed_control_handle_, MenuHandler::UNCHECKED);
01123 
01124   initControlMarkers();
01125 }
01126 
01127 void PR2MarkerControl::gripperToggleControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01128 {
01129   control_state_.r_gripper_.edit_control_ ^= true;
01130   control_state_.l_gripper_.edit_control_ ^= true;
01131 
01132   // TODO right now I'm assuming these will always be in the same state together...
01133   if(control_state_.r_gripper_.edit_control_)
01134     menu_grippers_.setCheckState(gripper_edit_control_handle_, MenuHandler::CHECKED);
01135   else
01136     menu_grippers_.setCheckState(gripper_edit_control_handle_, MenuHandler::UNCHECKED);
01137 
01138   initControlMarkers();
01139 }
01140 
01141 void PR2MarkerControl::dualGripperToggleControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01142 {
01143   control_state_.dual_grippers_.edit_control_ ^= true;
01144 
01145   if(control_state_.dual_grippers_.edit_control_)
01146     menu_dual_grippers_.setCheckState(dual_gripper_edit_control_handle_, MenuHandler::CHECKED);
01147   else
01148     menu_dual_grippers_.setCheckState(dual_gripper_edit_control_handle_, MenuHandler::UNCHECKED);
01149 
01150   ROS_INFO("toggling dual gripper edit control frame, current state is %d", control_state_.dual_grippers_.edit_control_);
01151 
01152   initControlMarkers();
01153 }
01154 
01155 void PR2MarkerControl::gripperResetControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01156 {
01157   int arm_id = -1;
01158   if(!feedback->marker_name.compare("r_gripper_control"))
01159     arm_id = 0;
01160   else if(!feedback->marker_name.compare("l_gripper_control"))
01161     arm_id = 1;
01162   else
01163   {
01164     ROS_ERROR("Marker name [%s] not recognized...", feedback->marker_name.c_str());
01165     return;
01166   }
01167   pose_offset_[arm_id].setOrigin(tf::Vector3(0.1, 0, 0));
01168   pose_offset_[arm_id].setRotation(tf::Quaternion(0, 0, 0, 1));
01169 }
01170 
01171 void PR2MarkerControl::dualGripperResetControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01172 {
01173   dual_pose_offset_.setOrigin(tf::Vector3(0, 0, 0));
01174   dual_pose_offset_.setRotation(tf::Quaternion(0, 0, 0, 1));
01175   initControlMarkers();
01176 }
01177 
01178 
01179 void PR2MarkerControl::startDualGrippers( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, bool active )
01180 {
01181   control_state_.dual_grippers_.on_ = active;
01182 
01183   // right and left gripper transforms to base, and right and left transforms to middle frame
01184   tf::Transform b_T_rw, b_T_lw, b_T_rt, b_T_lt;
01185 
01186   if(active)
01187   {
01188     //disable edit control mode in both grippers, in case they were on when we switched
01189     control_state_.r_gripper_.edit_control_ = false;
01190     control_state_.l_gripper_.edit_control_ = false;
01191     menu_grippers_.setCheckState(gripper_edit_control_handle_, MenuHandler::UNCHECKED);
01192 
01193     geometry_msgs::PoseStamped right_tool, left_tool;
01194     geometry_msgs::PoseStamped right_wrist = mechanism_.getGripperPose("right_arm", feedback->header.frame_id);
01195     geometry_msgs::PoseStamped left_wrist  = mechanism_.getGripperPose("left_arm", feedback->header.frame_id);
01196     right_tool = wristToTool(right_wrist);
01197     left_tool  = wristToTool(left_wrist);
01198     tf::poseMsgToTF(right_wrist.pose, b_T_rw);
01199     tf::poseMsgToTF(left_wrist.pose, b_T_lw);
01200     tf::poseMsgToTF(right_tool.pose, b_T_rt);
01201     tf::poseMsgToTF(left_tool.pose, b_T_lt);
01202 
01203     // compute midpoint frame using tool frames!
01204     tf::Vector3 midpoint = b_T_rt.getOrigin() + 0.5*(b_T_lt.getOrigin() - b_T_rt.getOrigin());
01205     // TODO this orientation is in the wrong frame!
01206     // Even if we set the correct torso frame initially, I suppose we need to continue
01207     // updating it if the robot drives around...
01208     tf::Transform b_T_m = tf::Transform(tf::Quaternion(0,0,0,1), midpoint);
01209 
01210     //compute gripper wrist offsets using wrist frames!
01211     dual_gripper_offsets_[0] = b_T_m.inverse()*b_T_rw;
01212     dual_gripper_offsets_[1] = b_T_m.inverse()*b_T_lw;
01213 
01214     //control frame offset from default dual gripper frame
01215     dual_pose_offset_ = tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0));
01216     control_state_.dual_grippers_.edit_control_ = false;
01217     menu_dual_grippers_.setCheckState(dual_gripper_edit_control_handle_, MenuHandler::UNCHECKED);
01218     control_state_.dual_grippers_.torso_frame_ = true;
01219     menu_dual_grippers_.setCheckState(dual_gripper_fixed_control_handle_, MenuHandler::CHECKED);
01220 
01221     dual_grippers_frame_ = msg::createPoseStampedMsg(b_T_m, feedback->header.frame_id, ros::Time(0)); // Time(0) prevents disappearing markers bug.
01222   }
01223 
01224   initControlMarkers();
01225 }
01226 
01227 void PR2MarkerControl::commandGripperPose(const geometry_msgs::PoseStamped &ps, int arm_id, bool use_offset)
01228 {
01229   std::string arm = "right_arm";
01230   if(arm_id == 1) arm = "left_arm";
01231   const char *arm_name = arm.c_str();
01232 
01233   tf::Transform control_pose, command_pose;
01234   tf::poseMsgToTF(ps.pose, control_pose);
01235   if(use_offset)
01236     command_pose = control_pose * pose_offset_[arm_id].inverse();
01237   else
01238     command_pose = control_pose;
01239   double dummy_var = 0;
01240   geometry_msgs::PoseStamped desired_pose = mechanism_.clipDesiredPose(arm_name,
01241                                                                        msg::createPoseStampedMsg(command_pose, ps.header.frame_id, ros::Time::now()),
01242                                                                        cartesian_clip_distance_*update_period_,
01243                                                                        cartesian_clip_angle_*update_period_,
01244                                                                        dummy_var);
01245 
01246   ROS_DEBUG_STREAM("sending gripper command in frame " << desired_pose.header.frame_id << "(" 
01247                   << desired_pose.pose.position.x << ", " 
01248                   << desired_pose.pose.position.y << ", " 
01249                   << desired_pose.pose.position.z << ")" );
01250 
01251   try {
01252     mechanism_.sendCartesianPoseCommand( arm_name, desired_pose);
01253   }
01254   catch ( std::runtime_error &e )
01255   {
01256     ROS_ERROR("Caught exception while sending pose command: %s", e.what( ));
01257   }
01258 }
01259 
01260 
01261 void PR2MarkerControl::updateGripper( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id )
01262 {
01263   ros::Time now = ros::Time(0);
01264   std::string arm = "right_arm";
01265   if(arm_id == 1) arm = "left_arm";
01266   const char *arm_name = arm.c_str();
01267 
01268   switch ( feedback->event_type )
01269   {
01270   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
01271       try {
01272         mechanism_.sendCartesianPoseCommand( arm_name, mechanism_.getGripperPose(arm_name, feedback->header.frame_id));
01273       }
01274       catch ( std::runtime_error &e )
01275       {
01276         ROS_ERROR("Caught exception while sending pose command: %s", e.what( ));
01277       }
01278       break;
01279 
01280   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
01281     // TODO still assuming l and r will always be in sync... this is probably BAD...
01282     if(control_state_.r_gripper_.edit_control_ )
01283     {
01284       geometry_msgs::PoseStamped ps = object_manipulator::msg::createPoseStampedMsg(feedback->pose,
01285                                                                                     feedback->header.frame_id,
01286                                                                                     ros::Time(0));
01287       if(!strcmp(arm_name, "right_arm"))
01288         tfl_.transformPose("r_wrist_roll_link", ps, ps );
01289       if(!strcmp(arm_name, "left_arm"))
01290         tfl_.transformPose("l_wrist_roll_link", ps, ps );
01291 
01292       tf::poseMsgToTF(ps.pose, pose_offset_[arm_id]);
01293     }
01294     else
01295     {
01296       //geometry_msgs::PoseStamped ps = object_manipulator::msg::createPoseStampedMsg(
01297       //                                              feedback->pose, feedback->header.frame_id, ros::Time(0));
01298       //tfl_.transformPose("/base_link", ps, ps );
01299 //      tf::Transform control_pose;
01300 //      tf::poseMsgToTF(feedback->pose, control_pose);
01301 //      tf::Transform command_pose = control_pose * pose_offset_[arm_id].inverse();
01302 
01303       ROS_DEBUG_STREAM("got updated gripper pose in frame " << feedback->header.frame_id);
01304 
01305       geometry_msgs::PoseStamped ps = object_manipulator::msg::createPoseStampedMsg(
01306                                                     feedback->pose, feedback->header.frame_id, feedback->header.stamp);
01307       commandGripperPose(ps, arm_id, true);
01308     }
01309     break;
01310   }
01311 }
01312 
01313 void PR2MarkerControl::updateDualGripper( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01314 {
01315   ros::Time now = ros::Time(0);
01316   if(!control_state_.dual_grippers_.on_) return;
01317 
01318   //float half_width = 0.15;  // TODO this should be controllable in some way!
01319 
01320   switch ( feedback->event_type )
01321   {
01322   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
01323       try {
01324         mechanism_.sendCartesianPoseCommand( "right_arm", mechanism_.getGripperPose("right_arm", feedback->header.frame_id));
01325         mechanism_.sendCartesianPoseCommand( "left_arm",  mechanism_.getGripperPose("left_arm",  feedback->header.frame_id));
01326       }
01327       catch ( std::runtime_error &e )
01328       {
01329         ROS_ERROR("Caught exception while sending pose command: %s", e.what( ));
01330       }
01331       break;
01332 
01333   case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
01334     // TODO still assuming l and r will always be in sync... this is probably BAD...
01335 //    if(control_state_.r_gripper_.edit_control_ )
01336 //    {
01337 //      geometry_msgs::PoseStamped ps = object_manipulator::msg::createPoseStampedMsg(feedback->pose,
01338 //                                                                                    feedback->header.frame_id,
01339 //                                                                                    ros::Time(0));
01340 //      if(!strcmp(arm_name, "right_arm"))
01341 //        tfl_.transformPose("r_wrist_roll_link", ps, ps );
01342 //      if(!strcmp(arm_name, "left_arm"))
01343 //        tfl_.transformPose("l_wrist_roll_link", ps, ps );
01344 //
01345 //      tf::poseMsgToTF(ps.pose, pose_offset_[arm_id]);
01346 //    }
01347 //    else
01348     {
01349       if(control_state_.dual_grippers_.edit_control_ )
01350       {
01351         geometry_msgs::PoseStamped ps = object_manipulator::msg::createPoseStampedMsg(feedback->pose,
01352                                                                                       feedback->header.frame_id,
01353                                                                                       ros::Time(0));
01354         tfl_.transformPose(dual_grippers_frame_.header.frame_id, ps, ps ); 
01355         tf::Transform feedback_trans;
01356         tf::poseMsgToTF(ps.pose, feedback_trans);
01357         tf::Transform dual_pose_offset_tf;
01358         tf::Transform dual_grippers_frame_tf;
01359         tf::poseMsgToTF(dual_grippers_frame_.pose, dual_grippers_frame_tf);
01360         dual_pose_offset_ = feedback_trans.inverse() * dual_grippers_frame_tf;
01361       }
01362       else
01363       {
01364         tf::Transform command_pose;
01365 
01366         tf::poseMsgToTF(feedback->pose, command_pose);
01367         //tf::Transform command_pose = control_pose * pose_offset_[arm_id].inverse();
01368 
01369         double dummy_var = 0;
01370         tf::Transform offset_command_pose_tf = command_pose * dual_pose_offset_;
01371         geometry_msgs::Pose offset_command_pose;
01372         tf::poseTFToMsg(offset_command_pose_tf, offset_command_pose);
01373         geometry_msgs::PoseStamped offset_command_pose_stamped = msg::createPoseStampedMsg(offset_command_pose, feedback->header.frame_id, now);
01374         geometry_msgs::PoseStamped desired_pose =
01375           mechanism_.clipDesiredPose(dual_grippers_frame_,
01376                                      offset_command_pose_stamped,
01377                                      0.3*cartesian_clip_distance_*update_period_,
01378                                      0.3*cartesian_clip_angle_*update_period_,
01379                                      dummy_var);
01380 
01381         // compute left and right gripper poses
01382         tf::Transform b_T_m, b_T_r, b_T_l;
01383         tf::poseMsgToTF(desired_pose.pose, b_T_m);
01384         b_T_r = b_T_m * dual_gripper_offsets_[0];
01385         b_T_l = b_T_m * dual_gripper_offsets_[1];
01386         geometry_msgs::PoseStamped right_pose = msg::createPoseStampedMsg(b_T_r, feedback->header.frame_id, ros::Time(0));
01387         geometry_msgs::PoseStamped left_pose =  msg::createPoseStampedMsg(b_T_l, feedback->header.frame_id, ros::Time(0));
01388 
01389         //store new dual_grippers_frame_
01390         dual_grippers_frame_ = desired_pose;
01391 
01392         // send the commands
01393         try {
01394           mechanism_.sendCartesianPoseCommand( "right_arm", right_pose);
01395           mechanism_.sendCartesianPoseCommand( "left_arm",  left_pose);
01396         }
01397         catch ( std::runtime_error &e )
01398         {
01399           ROS_ERROR("Caught exception while sending pose command: %s", e.what( ));
01400         }
01401       }
01402     }
01403     break;
01404   }
01405 }
01406 
01407 
01408 
01410 void PR2MarkerControl::gripperButtonCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, std::string action)
01411 {
01412   if (interface_number_ != 0 && interface_number_ != 1) return;
01413 
01414   std::string arm_name = getArmNameFromMarkerName(feedback->marker_name);
01415 
01416   if(arm_name == "right_arm")
01417   {
01418     if(action == "toggle") control_state_.r_gripper_.on_ ^= true;
01419     else if(action == "turn on") control_state_.r_gripper_.on_ = true;
01420     else control_state_.r_gripper_.on_ = false;
01421   }
01422   if(arm_name == "left_arm")
01423   {
01424     if(action == "toggle") control_state_.l_gripper_.on_ ^= true;
01425     else if(action == "turn on") control_state_.l_gripper_.on_ = true;
01426     else control_state_.l_gripper_.on_ = false;
01427   }
01428 
01429   if ( control_state_.r_gripper_.on_ || control_state_.l_gripper_.on_ ||
01430        control_state_.posture_r_ || control_state_.posture_l_ )
01431   {
01432     switchToCartesian();
01433   }
01434   else
01435   {
01436     switchToJoint();
01437   }
01438   initAllMarkers();
01439 }
01440 
01441 void PR2MarkerControl::upperArmButtonCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int id)
01442 {
01443   if (interface_number_ > 2) return;
01444 
01445   if(id == 0)
01446     control_state_.posture_r_ ^= true;
01447   if(id == 1)
01448     control_state_.posture_l_ ^= true;
01449 
01450   //always switch to Cartesian, so that joint trajectories are stopped in a hurry (e-stop)
01451   switchToCartesian();
01452 
01453   /*
01454   if ( control_state_.r_gripper_.on_ || control_state_.l_gripper_.on_ ||
01455        control_state_.posture_r_ || control_state_.posture_l_ )
01456   {
01457     switchToCartesian();
01458   }
01459   else
01460   {
01461     switchToJoint();
01462     }*/
01463   initAllMarkers();
01464 }
01465 
01466 void PR2MarkerControl::updatePosture( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id )
01467 {
01468   std::string arm_name = "right_arm";
01469   if(arm_id == 1) arm_name = "left_arm";
01470 
01471   std::vector<double> arm_angles(7);
01472   //mechanism_.getArmAngles(arm_name, arm_angles);
01473 
01474   switch ( feedback->event_type )
01475   {
01476     case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
01477     {
01478       // This value (9999) disables the posture control for the joint.
01479       for( size_t i = 0; i < arm_angles.size(); i++) arm_angles[i] = 9999;
01480       mechanism_.sendCartesianPostureCommand(arm_name, arm_angles);
01481       break;
01482     }
01483     case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
01484     {
01485       tf::Quaternion q;
01486       tf::quaternionMsgToTF(feedback->pose.orientation, q);
01487       float angle = q.getAngle()*q.getAxis().dot(tf::Vector3(1,0,0));
01488 
01489       for( size_t i = 0; i < arm_angles.size(); i++) arm_angles[i] = 9999;
01490       arm_angles[2] = angle;
01491       mechanism_.sendCartesianPostureCommand(arm_name, arm_angles);
01492       break;
01493     }
01494   }
01495 }
01496 
01497 /*
01498 void PR2MarkerControl::controllerSelectMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
01499 {
01500   MenuHandler::EntryHandle handle = feedback->menu_entry_id;
01501   MenuHandler::CheckState state;
01502 
01503   if(!menu_arms_.getCheckState(handle, state))  return;
01504   if ( handle == joint_handle_ )
01505   {
01506     switchToJoint();
01507     control_state_.r_gripper_.on_ = false;
01508     control_state_.l_gripper_.on_ = false;
01509   }
01510   if ( handle == jtranspose_handle_ )
01511   {
01512     switchToCartesian();
01513   }
01514 
01515   initAllMarkers();
01516   }*/
01517 
01518 void PR2MarkerControl::updateTorso( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
01519 {
01520   switch ( feedback->event_type )
01521   {
01522   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
01523     if(!feedback->control_name.compare("up"))
01524       torso_client_.top();
01525     else if(!feedback->control_name.compare("down"))
01526       torso_client_.bottom();
01527     else
01528       ROS_ERROR("Marker control unrecognized, this is an error in the client implementation!");
01529     break;
01530   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
01531     {
01532       arm_navigation_msgs::RobotState robot_state;
01533       mechanism_.getRobotState(robot_state);
01534       torso_client_.moveTo( getJointPosition("torso_lift_joint", robot_state) );
01535       break;
01536     }
01537   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
01538     break;
01539   }
01540 }
01541 
01542 
01543 void PR2MarkerControl::updateBase( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
01544 {
01545   geometry_msgs::TwistStamped ts;
01546   ts.header.stamp = ros::Time::now();
01547   ts.header.frame_id = "/base_link";
01548 
01549   tf::Vector3 linear  = tf::Vector3(0,0,0);
01550   tf::Vector3 angular = tf::Vector3(0,0,0);
01551 
01552   switch ( feedback->event_type )
01553   {
01554   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
01555   {
01556 
01557     tf::Quaternion q;
01558     tf::quaternionMsgToTF(feedback->pose.orientation, q);
01559     tf::Matrix3x3 mat(q);
01560 
01561     if(!feedback->control_name.compare("forward"))  linear = tf::Vector3( 1, 0, 0);
01562     if(!feedback->control_name.compare("back"))     linear = tf::Vector3(-1, 0, 0);
01563     if(!feedback->control_name.compare("left"))     linear = tf::Vector3( 0, 1, 0);
01564     if(!feedback->control_name.compare("right"))    linear = tf::Vector3( 0,-1, 0);
01565     if(!feedback->control_name.compare("rotate right"))  angular = tf::Vector3(0, 0,-1);
01566     if(!feedback->control_name.compare("rotate left"))   angular = tf::Vector3(0, 0, 1);
01567 
01568     linear = 0.3*(mat*linear);
01569     angular = 0.5*angular;
01570 
01571     tf::vector3TFToMsg(linear, ts.twist.linear);
01572     tf::vector3TFToMsg(angular, ts.twist.angular);
01573 
01574     base_client_.applyTwist(ts);
01575     break;
01576   }
01577   case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
01578     base_client_.applyTwist(ts);
01579     break;
01580   case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
01581     break;
01582   }
01583 }
01584 
01585 void PR2MarkerControl::torsoMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
01586 {
01587   if(!feedback->control_name.compare("up"))
01588     torso_client_.top();
01589   else if(!feedback->control_name.compare("down"))
01590     torso_client_.bottom();
01591   else
01592     ROS_ERROR("Marker control unrecognized, this is an error in the client implementation!");
01593 }
01594 
01595 
01596 void PR2MarkerControl::gripperClosureCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const float &command)
01597 {
01598   std::string arm_name = getArmNameFromMarkerName(feedback->marker_name);
01599   double open = gripper_client_.getGripperOpenGap(arm_name);
01600   double closed = gripper_client_.getGripperClosedGap(arm_name);
01601   double value = closed + (open - closed) * command;
01602 
01603   if( arm_name != "" )
01604   {
01605     gripper_client_.commandGripperValue(arm_name, value);
01606   }
01607   else
01608     ROS_ERROR("Marker name [%s] not handled!", feedback->marker_name.c_str());
01609 
01610   //if opening the gripper, reset attached objects for that arm
01611   if (value > closed + (open - closed)/2.)
01612     mechanism_.detachAllObjectsFromGripper(arm_name);
01613 }
01614 
01615 void PR2MarkerControl::requestGripperPose(  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback,
01616                                             int arm_id)
01617 {
01618   std::string arm_name;
01619   if(!feedback->marker_name.compare("r_gripper_control")){
01620     arm_name = "right_arm";
01621   }
01622   else if(!feedback->marker_name.compare("l_gripper_control"))
01623   {
01624     arm_name = "left_arm";
01625   }
01626   else
01627   {
01628     ROS_ERROR("Marker name [%s] not recognized...", feedback->marker_name.c_str());
01629     return;
01630   }
01631 
01632   pr2_object_manipulation_msgs::GetGripperPoseGoal goal;
01633   goal.arm_name = arm_name;
01634   goal.gripper_opening = 0.08;
01635   if(arm_name == "right_arm") goal.gripper_pose = mechanism_.getGripperPose(arm_name, "torso_lift_link");
01636   if(arm_name == "left_arm") goal.gripper_pose = mechanism_.getGripperPose(arm_name, "torso_lift_link");
01637   gripper_pose_client_.client().sendGoal( goal,
01638                                           boost::bind(&PR2MarkerControl::processGripperPoseResult, this, _1, _2, arm_name),
01639                                           actionlib::SimpleActionClient<pr2_object_manipulation_msgs::GetGripperPoseAction>::SimpleActiveCallback(),
01640                                           //actionlib::SimpleActionClient<pr2_object_manipulation_msgs::GetGripperPoseAction>::SimpleFeedbackCallback());//,
01641                                           boost::bind(&PR2MarkerControl::processGripperPoseFeedback, this, _1, arm_name) );
01642   
01643   control_state_.r_gripper_.on_ = false;
01644   control_state_.l_gripper_.on_ = false;
01645   initControlMarkers();
01646 }
01647 
01648 void PR2MarkerControl::processGripperPoseFeedback(  const pr2_object_manipulation_msgs::GetGripperPoseFeedbackConstPtr &result,
01649                                                     const std::string &arm_name)
01650 {
01651   int arm_id = 0;
01652   if(arm_name == "left_arm") arm_id = 1;
01653 
01654   commandGripperPose(result->gripper_pose, arm_id, false);
01655 
01656 }
01657 
01658 void PR2MarkerControl::processGripperPoseResult(  const actionlib::SimpleClientGoalState& state,
01659                                                   const pr2_object_manipulation_msgs::GetGripperPoseResultConstPtr &result,
01660                                                   const std::string &arm_name)
01661 {
01662   ROS_ERROR("We should be setting the state back to 'controls active' here.");
01663   control_state_.r_gripper_.on_ = true;
01664   control_state_.l_gripper_.on_ = true;
01665   initControlMarkers();
01666 }
01667 
01668 void PR2MarkerControl::moveArm( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const std::string &position,
01669               bool planner)
01670 {
01671   std::string arm_name;
01672   if( feedback->marker_name == "r_upper_arm_link" || feedback->marker_name == "r_gripper_palm_link" )
01673     arm_name = "right_arm";
01674   else if( feedback->marker_name == "l_upper_arm_link" || feedback->marker_name == "l_gripper_palm_link" )
01675     arm_name = "left_arm";
01676   else
01677     ROS_WARN("Marker name [%s] not handled!", feedback->marker_name.c_str());
01678 
01679   std::string move_type = (planner)?("with planner"):("open-loop");
01680   ROS_INFO("moving %s to %s %s", arm_name.c_str(), position.c_str(), move_type.c_str());
01681   sys_thread_.reset( new boost::thread( boost::bind(
01682               &PR2MarkerControl::moveArmThread, this, arm_name, position, true, planner ) ) );
01683 }
01684 
01685 
01686 void PR2MarkerControl::moveArmThread(std::string arm_name, std::string position, bool collision, bool planner)
01687 {
01688   if (interface_number_ != 0) gripper_client_.commandGripperValue(arm_name, gripper_client_.getGripperOpenGap(arm_name));
01689   try
01690   {
01691     ROS_DEBUG("Attempting arm motion");
01692     arm_navigation_msgs::OrderedCollisionOperations ord;
01693     if (!collision)
01694     {
01695       arm_navigation_msgs::CollisionOperation coll;
01696       coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL;
01697       coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL;
01698       coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE;
01699       ord.collision_operations.push_back(coll);
01700     }
01701     std::vector<arm_navigation_msgs::LinkPadding> pad;
01702     if (collision)
01703     {
01704       pad = object_manipulator::concat( object_manipulator::MechanismInterface::gripperPadding("left_arm", 0.0),
01705                                         object_manipulator::MechanismInterface::gripperPadding("right_arm", 0.0) );
01706     }
01707     if (planner)
01708     {
01709       //ompl will crash if move_arm for the right and left arms try to plan at the same time, so lock to make sure we don't send two goals at once
01710       if(planner_lock_.try_lock())
01711       {
01712         ROS_INFO("Locking to attemptMoveArmToGoal for %s", arm_name.c_str());
01713 
01714         //clear any current move arm goals if there are any running before trying to issue our own
01715         mechanism_.clearMoveArmGoals();
01716 
01717         //trying move_arm twice, resetting map if stuck, timeout of 30 seconds
01718         mechanism_.attemptMoveArmToGoal(arm_name,
01719                                         object_manipulator::armConfigurations().position(arm_name, position), ord, pad, 2, true, 30.);
01720         planner_lock_.unlock();
01721         ROS_INFO("moveArmThread for %s released lock", arm_name.c_str());
01722       }
01723       //if we're already asking move_arm to do something, try to cancel goals and then try again
01724       else
01725       {
01726         ROS_INFO("marker control: Failed to get lock when trying to move %s!  Clearing move arm goals twice", arm_name.c_str());
01727 
01728         //clear goals twice, since we always try twice
01729         mechanism_.clearMoveArmGoals();
01730         ros::Duration(0.25).sleep();
01731         ROS_INFO("marker control: clearing move arm goals a second time");
01732         mechanism_.clearMoveArmGoals();
01733         ROS_INFO("marker control: done clearing move arm goals before moving %s", arm_name.c_str());
01734         if(planner_lock_.try_lock())
01735         {
01736           ROS_INFO("Got lock this time, locking to attemptMoveArmToGoal for %s", arm_name.c_str());
01737           //trying twice, resetting map if stuck, timeout of 30 seconds
01738           mechanism_.attemptMoveArmToGoal(arm_name,
01739                                           object_manipulator::armConfigurations().position(arm_name, position), ord, pad, 2, true, 30.);
01740           planner_lock_.unlock();
01741           ROS_INFO("released lock after moving %s", arm_name.c_str());
01742         }
01743         else
01744         {
01745           ROS_INFO("Failed to get lock again when trying to move %s, giving up", arm_name.c_str());
01746         }
01747       }
01748     }
01749     else
01750     {
01751       mechanism_.attemptTrajectory(arm_name, object_manipulator::armConfigurations().trajectory(arm_name, position),
01752                                    false, 2.0);
01753     }
01754   }
01755   catch (object_manipulator::ServiceNotFoundException &ex)
01756   {
01757     ROS_ERROR("a needed service or action server was not found");
01758   }
01759   catch (object_manipulator::MoveArmStuckException &ex)
01760   {
01761     ROS_ERROR("arm is stuck in a colliding position");
01762     planner_lock_.unlock();
01763   }
01764   catch (object_manipulator::MissingParamException &ex)
01765   {
01766     ROS_ERROR("parameters missing; is manipulation pipeline running?");
01767   }
01768   catch (object_manipulator::MechanismException &ex)
01769   {
01770     ROS_ERROR("Error: %s", ex.what());
01771     planner_lock_.unlock();
01772   }
01773   catch (...)
01774   {
01775     ROS_ERROR("an unknown error has occured, please call helpdesk");
01776     planner_lock_.unlock();
01777   }
01778 
01779   // Interface 1 (cartesian teleop) should always pop up the control rings.
01780   if(interface_number_ == 1)
01781   {
01782     switchToCartesian();
01783     control_state_.r_gripper_.on_ = true;
01784     //control_state_.posture_r_ = true;
01785     initAllMarkers();
01786   }
01787   // Auto-refresh / reset collision map is useful when running with novice users.
01788   if(interface_number_ != 0){
01789     snapshot_client_.refresh( nh_.resolveName("snapshot_input_topic", true) );
01790     std_srvs::Empty srv;
01791     if (!collider_node_reset_srv_.client().call(srv)) ROS_ERROR("failed to reset collision map!");
01792   }
01793 }
01794 
01795 
01796 void PR2MarkerControl::requestNavGoal(const bool &collision_aware)
01797 {
01798   //ROS_WARN("Starting requestNavGoal");
01799   // First call the 'get pose' action so that the user is distracted.
01800   pr2_object_manipulation_msgs::GetNavPoseGoal goal;
01801   goal.max_distance = collision_aware ? (-1.0): (max_direct_nav_radius_);
01802   base_pose_client_.client().sendGoal( goal, boost::bind(&PR2MarkerControl::processNavGoal, this, _1, _2, collision_aware));
01803 
01804   if( using_3d_nav_ ) 
01805   {
01806     ROS_INFO("Using 3D navigation, not changing global or local planners");
01807     return;
01808   }
01809 
01810   // While the user is using the requested action, configure the planner in the background. 
01811   std::string reconfigure = "rosrun dynamic_reconfigure dynparam set ";
01812   std::string move_base_config, costmap_config;
01813   
01814   if( collision_aware )
01815   {
01816     ROS_INFO("Activating 'global' planner.");
01817     // Don't just use "restore_defaults: true" because it restores whatever was on the param server when the node started."
01818 
01819     // We could dynamically set the footprint of the robot based on the arm pose during these calls!
01820     move_base_config = reconfigure + move_base_node_name_ + " "
01821                        + "\"{'base_global_planner': 'navfn/NavfnROS', "
01822                        + "   'base_local_planner' : 'dwa_local_planner/DWAPlannerROS'}\" ";
01823     costmap_config = reconfigure + move_base_node_name_ + "/local_costmap \"{ "
01824                      + "'max_obstacle_height' : 2.0, 'inflation_radius' : 0.55 }\" ";
01825   }
01826   else
01827   {
01828     ROS_INFO("Activating 'local' planner.");
01829     move_base_config = reconfigure + move_base_node_name_ +" "
01830 //                       + "\"{'base_global_planner': 'navfn/NavfnROS', "
01831                        + "\"{'base_global_planner': 'pr2_navigation_controllers/GoalPasser', "
01832                        + "   'base_local_planner' : 'pr2_navigation_controllers/PoseFollower'}\" ";
01833     
01834     costmap_config = reconfigure + move_base_node_name_ + "/local_costmap \"{ "
01835                      + "'max_obstacle_height' : 0.36 , 'inflation_radius': 0.01 }\" ";
01836   }
01837 
01838   //ROS_WARN("Setting planners...");
01839   int ok = system(move_base_config.c_str());
01840   if(ok < 0)
01841     ROS_ERROR("Dynamic reconfigure for move_base_node FAILED!");
01842   //ROS_WARN("Setting costmap configuration...");
01843   ok = system(costmap_config.c_str());
01844   if(ok < 0)
01845     ROS_ERROR("Dynamic reconfigure for move_base_node/local_costmap FAILED!");  
01846   ROS_INFO("Done!");
01847   //ROS_WARN("Exiting requestNavGoal");
01848 }
01849 
01850 void PR2MarkerControl::processNavGoal(  const actionlib::SimpleClientGoalState& state,
01851                                         const pr2_object_manipulation_msgs::GetNavPoseResultConstPtr &result,
01852                                         const bool &collision_aware )
01853 {
01854   if(state.state_ == state.SUCCEEDED)
01855   {
01856     ROS_DEBUG("Got a valid base pose.");
01857     base_goal_pose_ = result->pose;
01858     sendLastNavGoal();
01859   }
01860   else
01861   {
01862     ROS_WARN("Get Base Pose Action did not succeed; state = %d", (int)state.state_);
01863   }
01864 }
01865 
01866 void PR2MarkerControl::requestBasePoseEstimate()
01867 {
01868   pr2_object_manipulation_msgs::GetNavPoseGoal goal;
01869   goal.max_distance = -1.0;
01870   base_pose_client_.client().sendGoal( goal, boost::bind(&PR2MarkerControl::processBasePoseEstimate, this, _1, _2));
01871 }
01872 
01873 
01874 void PR2MarkerControl::processBasePoseEstimate( const actionlib::SimpleClientGoalState& state,
01875                                                 const pr2_object_manipulation_msgs::GetNavPoseResultConstPtr &result )
01876 {
01877   if(state.state_ == state.SUCCEEDED)
01878   {
01879     ROS_DEBUG("Got a valid estimate for base pose.");
01880     geometry_msgs::PoseWithCovarianceStamped ps;
01881     ps.pose.pose = result->pose.pose;
01882     ps.pose.pose.position.z = 0;  //enforce 0 ground-plane position
01883     ps.header = result->pose.header;
01884 
01885     //Covariance values taken from what Rviz publishes... no idea if these are optimal though.
01886     ps.pose.covariance.at(6*0 + 0) = 0.25;
01887     ps.pose.covariance.at(6*1 + 1) = 0.25;
01888     ps.pose.covariance.at(6*5 + 5) = 0.06853891945200942;
01889 
01890     base_client_.sendPoseEstimate(ps);
01891   }
01892   else
01893   {
01894     ROS_WARN("Get Base Pose Action did not succeed; state = %d", (int)state.state_);
01895   }
01896 }
01897 
01898 void PR2MarkerControl::sendLastNavGoal()
01899 {
01900     if( (ros::Time::now() - base_goal_pose_.header.stamp).toSec() < 60.0 )
01901     {
01902         ROS_INFO("Sending last base goal pose");
01903         base_client_.sendNavGoal( base_goal_pose_ );
01904     }
01905     else
01906     {
01907         base_goal_pose_ = geometry_msgs::PoseStamped();
01908         base_goal_pose_.header.frame_id = "base_link";
01909         base_goal_pose_.pose.orientation.w = 1; 
01910         ROS_INFO("Last goal was from too long ago; sending identity base goal pose");
01911         base_client_.sendNavGoal( base_goal_pose_ );
01912     }
01913 }
01914 
01915 void PR2MarkerControl::clearLocalCostmap()
01916 {
01917     ROS_INFO("Clearing the navigation costmap...");
01918     base_client_.clearLocalCostmap( );
01919 }
01920 
01921 void PR2MarkerControl::inHandObjectRightCallback(const sensor_msgs::PointCloud2ConstPtr &cloud)
01922 {
01923   ROS_INFO("Got an in-hand object cloud for the right hand!");
01924   object_cloud_right_.updateCloud(*cloud, "in_hand_object_right");
01925 }
01926 
01927 void PR2MarkerControl::inHandObjectLeftCallback(const sensor_msgs::PointCloud2ConstPtr &cloud)
01928 {
01929   ROS_INFO("Got an in-hand object cloud for the left hand!");
01930   object_cloud_left_.updateCloud(*cloud, "in_hand_object_left");
01931 }
01932 
01933 void PR2MarkerControl::initMenus()
01934 {
01935   MenuHandler::EntryHandle handle;
01936 
01937   // - - - - - - - - - - Head Menu - - - - - - - - - - //
01938 
01939   menu_head_.insert("Take Snapshot", boost::bind( &PR2MarkerControl::snapshotCB, this ) );
01940 
01941   if (interface_number_ == 0)
01942   {
01943     head_target_handle_ = menu_head_.insert( "Target Point", boost::bind( &PR2MarkerControl::targetPointMenuCB,
01944                                                                           this, _1 ) );
01945     menu_head_.setCheckState(head_target_handle_, MenuHandler::UNCHECKED);
01946 
01947     projector_handle_ = menu_head_.insert("Projector", boost::bind( &PR2MarkerControl::projectorMenuCB,
01948                                                                     this, _1 ) );
01949     menu_head_.setCheckState(projector_handle_, MenuHandler::UNCHECKED);
01950 
01951     menu_head_.insert( "Move Head To Center", boost::bind( &PR2MarkerControl::centerHeadCB,
01952                                                            this ) );
01953   }
01954 
01955 
01956   // - - - - - - - - - - Arm Menu - - - - - - - - - - //
01957   if (interface_number_ == 0)
01958   {
01959     tuck_handle_ = menu_arms_.insert( "Tuck..." );
01960     menu_arms_.insert(tuck_handle_, "Untuck Both Arms",         boost::bind( &PR2MarkerControl::tuckArmsCB, this, false, false));
01961     menu_arms_.insert(tuck_handle_, "Untuck left, tuck right",  boost::bind( &PR2MarkerControl::tuckArmsCB, this, false, true ));
01962     menu_arms_.insert(tuck_handle_, "Tuck left, untuck right",  boost::bind( &PR2MarkerControl::tuckArmsCB, this, true, false ));
01963     menu_arms_.insert(tuck_handle_, "Tuck Both Arms",           boost::bind( &PR2MarkerControl::tuckArmsCB, this, true, true  ));
01964   }
01965 
01966   if (interface_number_ == 0)
01967   {
01968     handle = menu_arms_.insert( "Safe move to ... " );
01969     menu_arms_.insert( handle, "above", boost::bind( &PR2MarkerControl::moveArm, this, _1, "above", true  ) );
01970     menu_arms_.insert( handle, "side",  boost::bind( &PR2MarkerControl::moveArm, this, _1, "side", true  ) );
01971     menu_arms_.insert( handle, "front", boost::bind( &PR2MarkerControl::moveArm, this, _1, "front", true ) );
01972 
01973     handle = menu_arms_.insert( "Forced move to ... " );
01974     menu_arms_.insert( handle, "above", boost::bind( &PR2MarkerControl::moveArm, this, _1, "above", false  ) );
01975     menu_arms_.insert( handle, "side",  boost::bind( &PR2MarkerControl::moveArm, this, _1, "side", false  ) );
01976     menu_arms_.insert( handle, "front", boost::bind( &PR2MarkerControl::moveArm, this, _1, "front", false ) );
01977 
01978     handle = menu_arms_.insert( "Gripper commands" );
01979     menu_arms_.insert( handle, "Activate Cartesian control",
01980                        boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "turn on") );
01981     menu_arms_.insert( handle, "Turn off Cartesian control",
01982                        boost::bind( &PR2MarkerControl::gripperButtonCB, this, _1, "turn off") );
01983     menu_arms_.insert( handle, "Open Gripper",
01984                        boost::bind( &PR2MarkerControl::gripperClosureCB, this, _1, 1 ) );
01985     menu_arms_.insert( handle, "Close Gripper",
01986                        boost::bind( &PR2MarkerControl::gripperClosureCB, this, _1, 0 ) );
01987   }
01988   else
01989   {
01990     menu_arms_.insert( "Drop object and reset position",
01991                        boost::bind( &PR2MarkerControl::moveArm, this, _1, "side", true  ) );
01992   }
01993 
01994   // - - - - - - - - - - Gripper Control Menu - - - - - - - - - - //
01995 
01996   gripper_fixed_control_handle_ = menu_grippers_.insert( "Torso-Fixed Control",
01997                                                   boost::bind( &PR2MarkerControl::gripperToggleFixedCB, this, _1 ) );
01998   menu_grippers_.setCheckState(gripper_fixed_control_handle_, MenuHandler::CHECKED);
01999 
02000   if (interface_number_ == 0)
02001   {
02002     handle = menu_grippers_.insert( "Marker Mode" );
02003 
02004     gripper_6dof_handle_ = menu_grippers_.insert( handle, "6 DOF",
02005                                                   boost::bind( &PR2MarkerControl::gripperToggleModeCB, this, _1 ) );
02006     menu_grippers_.setCheckState(gripper_6dof_handle_, MenuHandler::CHECKED);
02007 
02008     gripper_view_facing_handle_ = menu_grippers_.insert( handle, "View Facing",
02009                                                   boost::bind( &PR2MarkerControl::gripperToggleModeCB, this, _1 ) );
02010     menu_grippers_.setCheckState(gripper_view_facing_handle_, MenuHandler::UNCHECKED);
02011 
02012     gripper_edit_control_handle_ = menu_grippers_.insert( "Edit Control Frame",
02013                                                boost::bind( &PR2MarkerControl::gripperToggleControlCB, this, _1 ) );
02014     menu_grippers_.setCheckState(gripper_edit_control_handle_, MenuHandler::UNCHECKED);
02015 
02016     gripper_reset_control_handle_ = menu_grippers_.insert( "Reset Control Frame",
02017                                                 boost::bind( &PR2MarkerControl::gripperResetControlCB, this, _1 ) );
02018     menu_grippers_.insert( "Dual Grippers", boost::bind( &PR2MarkerControl::startDualGrippers, this, _1, true ) );
02019     menu_grippers_.insert( "Collision-Constraint", boost::bind( &PR2MarkerControl::requestGripperPose, this, _1, 0 ) );
02020   }
02021 
02022   // - - - - - - - - - - Dual-Gripper Control Menu - - - - - - - - - - //
02023 
02024   if (interface_number_ == 0)
02025   {
02026     menu_dual_grippers_.insert( "Exit", boost::bind( &PR2MarkerControl::startDualGrippers, this, _1, false ) );
02027     dual_gripper_fixed_control_handle_ = menu_dual_grippers_.insert( "Torso-Fixed Control", 
02028                                               boost::bind( &PR2MarkerControl::dualGripperToggleFixedCB, this, _1 ) );
02029     menu_dual_grippers_.setCheckState(dual_gripper_edit_control_handle_, MenuHandler::CHECKED);
02030     dual_gripper_edit_control_handle_ = menu_dual_grippers_.insert( "Edit Control Frame", 
02031                                               boost::bind( &PR2MarkerControl::dualGripperToggleControlCB, this, _1 ) );
02032     menu_dual_grippers_.setCheckState(dual_gripper_edit_control_handle_, MenuHandler::UNCHECKED);
02033     dual_gripper_reset_control_handle_ = menu_dual_grippers_.insert( "Reset Control Frame", 
02034                                               boost::bind( &PR2MarkerControl::dualGripperResetControlCB, this, _1 ) );
02035   }
02036 
02037   // - - - - - - - - - - Gripper Closure Menu - - - - - - - - - - //
02038 
02039   if (interface_number_ < 3)
02040   {
02041     menu_gripper_close_.insert( "Open Gripper",  boost::bind( &PR2MarkerControl::gripperClosureCB, this, _1, 1 ) );
02042     menu_gripper_close_.insert( "Close Gripper", boost::bind( &PR2MarkerControl::gripperClosureCB, this, _1, 0 ) );
02043   }
02044   else
02045   {
02046     menu_gripper_close_.insert( "Drop object and reset position",
02047         boost::bind( &PR2MarkerControl::moveArm, this, _1, "side", true  ) );
02048   }
02049 
02050   // - - - - - - - - - - Torso Menu - - - - - - - - - - //
02051   menu_torso_.insert( "All the way", boost::bind( &PR2MarkerControl::torsoMenuCB, this, _1 ) );
02052 
02053   // - - - - - - - - - - Base Menu - - - - - - - - - - //
02054   menu_base_.insert( "Navigate to...",      boost::bind( &PR2MarkerControl::requestNavGoal, this, true ) );
02055   menu_base_.insert( "Directly Move to...", boost::bind( &PR2MarkerControl::requestNavGoal, this, false ) );
02056   menu_base_.insert( "Resume last Goal", boost::bind( &PR2MarkerControl::sendLastNavGoal, this ) );
02057   menu_base_.insert( "Clear costmaps", boost::bind( &PR2MarkerControl::clearLocalCostmap, this ) );
02058   menu_base_.insert( "Set Pose on Map", boost::bind( &PR2MarkerControl::requestBasePoseEstimate, this ) );
02059 }
02060 
02061 
02062 // Graveyard


pr2_marker_control
Author(s): Adam Leeper
autogenerated on Fri Jan 3 2014 12:07:28