00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #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 <object_manipulator/tools/mechanism_interface.h>
00043 #include <object_manipulator/tools/msg_helpers.h>
00044 #include <object_manipulator/tools/arm_configurations.h>
00045 #include <object_manipulator/tools/vector_tools.h>
00046 #include <object_manipulator/tools/service_action_wrappers.h>
00047
00048 #include <std_srvs/Empty.h>
00049
00050 #include <actionlib/client/simple_action_client.h>
00051 #include <actionlib/server/simple_action_server.h>
00052
00053 #include <boost/thread.hpp>
00054
00055 #include <tf/transform_listener.h>
00056 #include <tf/transform_broadcaster.h>
00057
00058 #include <pr2_wrappers/gripper_controller.h>
00059 #include <pr2_wrappers/torso_client.h>
00060 #include <pr2_wrappers/base_client.h>
00061 #include <pr2_wrappers/tuck_arms_client.h>
00062 #include <point_cloud_server/StoreCloudAction.h>
00063
00064 #include <pr2_object_manipulation_msgs/GetNavPoseAction.h>
00065 #include <pr2_object_manipulation_msgs/GetGripperPoseAction.h>
00066
00067 #include <interactive_marker_helpers/interactive_marker_helpers.h>
00068 #include <pr2_marker_control/cloud_handler.h>
00069
00070 #include <boost/thread/thread.hpp>
00071
00073 class PR2MarkerControl
00074 {
00075 public:
00076
00078 PR2MarkerControl();
00079
00081 virtual ~PR2MarkerControl() { switchToJoint(); }
00082
00083
00084
00086 void fastUpdate();
00087
00089 void slowUpdate();
00090
00092 double getJointPosition( std::string name, const arm_navigation_msgs::RobotState& robot_state);
00093
00095 geometry_msgs::PoseStamped toolToWrist(const geometry_msgs::PoseStamped &ps);
00096
00098 geometry_msgs::PoseStamped wristToTool(const geometry_msgs::PoseStamped &ps);
00099
00101 void initAllMarkers(bool apply_immediately = false)
00102 {
00103 initControlMarkers();
00104 initMeshMarkers();
00105
00106 if(apply_immediately)
00107 {
00108 ROS_INFO_STREAM( "Re-initializing all markers!" );
00109 server_.applyChanges();
00110 }
00111 }
00112
00114 void initControlMarkers();
00115
00117 void initMeshMarkers();
00118
00120 void cancelBaseMovement() {
00121 base_goal_pose_.header.stamp = ros::Time::now();
00122 base_client_.cancelGoals();
00123 }
00124
00125
00126 protected:
00127
00129 void switchToCartesian();
00130
00132 void switchToJoint();
00133
00135 bool checkStateValidity(std::string arm_name);
00136
00138 void gripperToggleModeCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00139
00140 void snapshotCB() { snapshot_client_.refresh( nh_.resolveName("snapshot_input_topic", true) ); }
00141
00142 void gripperToggleFixedCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00143
00144 void dualGripperToggleFixedCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00145
00146 void gripperToggleControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00147
00148 void dualGripperToggleControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00149
00150 void gripperResetControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00151
00152 void dualGripperResetControlCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00153
00154 void startDualGrippers( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, bool active );
00155
00156
00157 void updateGripper( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id );
00158
00159 void updateDualGripper( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00160
00162 void gripperButtonCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, std::string action);
00163
00164 void upperArmButtonCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int id);
00165
00166
00167 void baseButtonCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00168 {
00169 control_state_.base_on_ ^= true;
00170 initControlMarkers();
00171 }
00172
00173 void refreshPosture( const std::string &arm_name )
00174 {
00175 std::vector<double> arm_angles(7);
00176 for( size_t i = 0; i < arm_angles.size(); i++) arm_angles[i] = 9999;
00177 mechanism_.sendCartesianPostureCommand(arm_name, arm_angles);
00178 }
00179
00180 void tuckArmsCB( bool tuck_left, bool tuck_right)
00181 {
00182 switchToJoint();
00183 tuck_arms_client_.tuckArms( tuck_right, tuck_left, false );
00184 }
00185
00186 void updatePosture( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id );
00187
00188 void projectorMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00189
00190 void targetPointMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00191
00192 void centerHeadCB()
00193 {
00194 geometry_msgs::PointStamped ps;
00195 ps.header.frame_id = "/base_link";
00196 ps.point.x = 1.0;
00197 mechanism_.pointHeadAction(ps, head_pointing_frame_, false);
00198 }
00199
00200
00201
00202
00203 void updateTorso( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00204
00205 void updateBase( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00206
00207 void torsoMenuCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00208
00209 void gripperClosureCB( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const float &command);
00210
00211 void updateHeadGoal( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id );
00212
00213 void commandGripperPose(const geometry_msgs::PoseStamped &ps, int arm_id, bool use_offset);
00214
00215 void requestGripperPose( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, int arm_id);
00216
00217 void processGripperPoseFeedback( const pr2_object_manipulation_msgs::GetGripperPoseFeedbackConstPtr &result,
00218 const std::string &arm_name);
00219
00220 void processGripperPoseResult( const actionlib::SimpleClientGoalState& state,
00221 const pr2_object_manipulation_msgs::GetGripperPoseResultConstPtr &result,
00222 const std::string &arm_name);
00223
00224 void moveArm( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback,
00225 const std::string &position, bool planner);
00226
00227 void moveArmThread(std::string arm_name, std::string position, bool collision, bool planner);
00228
00229 void initMenus();
00230
00231 void requestNavGoal( const bool & collision_aware );
00232
00233 void processNavGoal( const actionlib::SimpleClientGoalState& state,
00234 const pr2_object_manipulation_msgs::GetNavPoseResultConstPtr &result,
00235 const bool &collision_aware );
00236
00237 void requestBasePoseEstimate( );
00238
00239
00240 void processBasePoseEstimate( const actionlib::SimpleClientGoalState& state,
00241 const pr2_object_manipulation_msgs::GetNavPoseResultConstPtr &result );
00242
00244 void sendLastNavGoal();
00245
00246 void clearLocalCostmap();
00247
00248 void inHandObjectRightCallback( const sensor_msgs::PointCloud2ConstPtr &cloud);
00249
00250 void inHandObjectLeftCallback( const sensor_msgs::PointCloud2ConstPtr &cloud);
00251
00252 protected:
00253
00254 ros::NodeHandle nh_;
00255 ros::NodeHandle pnh_;
00256 ros::Timer spin_timer_;
00257 ros::Timer slow_sync_timer_;
00258 interactive_markers::InteractiveMarkerServer server_;
00259
00260
00262 interactive_markers::MenuHandler menu_arms_;
00263 interactive_markers::MenuHandler menu_head_;
00264 interactive_markers::MenuHandler menu_torso_;
00265 interactive_markers::MenuHandler menu_laser_;
00266 interactive_markers::MenuHandler menu_grippers_;
00267 interactive_markers::MenuHandler menu_dual_grippers_;
00268 interactive_markers::MenuHandler menu_gripper_close_;
00269 interactive_markers::MenuHandler menu_base_;
00270
00272 interactive_markers::MenuHandler::EntryHandle tuck_handle_;
00273 interactive_markers::MenuHandler::EntryHandle joint_handle_;
00274 interactive_markers::MenuHandler::EntryHandle jtranspose_handle_;
00275 interactive_markers::MenuHandler::EntryHandle posture_handle_;
00276 interactive_markers::MenuHandler::EntryHandle projector_handle_;
00277 interactive_markers::MenuHandler::EntryHandle head_target_handle_;
00278 interactive_markers::MenuHandler::EntryHandle gripper_view_facing_handle_;
00279 interactive_markers::MenuHandler::EntryHandle gripper_6dof_handle_;
00280 interactive_markers::MenuHandler::EntryHandle gripper_fixed_control_handle_;
00281 interactive_markers::MenuHandler::EntryHandle dual_gripper_fixed_control_handle_;
00282 interactive_markers::MenuHandler::EntryHandle gripper_edit_control_handle_;
00283 interactive_markers::MenuHandler::EntryHandle dual_gripper_edit_control_handle_;
00284 interactive_markers::MenuHandler::EntryHandle gripper_reset_control_handle_;
00285 interactive_markers::MenuHandler::EntryHandle dual_gripper_reset_control_handle_;
00286
00287 tf::TransformListener tfl_;
00288 tf::TransformBroadcaster tfb_;
00289
00290 std::vector<tf::Transform> pose_offset_;
00291 tf::Transform dual_pose_offset_;
00292 geometry_msgs::Pose tool_frame_offset_;
00293 geometry_msgs::PoseStamped head_goal_pose_;
00294
00295 geometry_msgs::PoseStamped dual_grippers_frame_;
00296 std::vector<tf::Transform> dual_gripper_offsets_;
00297
00298 std::string manipulator_base_frame_;
00299
00300 geometry_msgs::PoseStamped base_goal_pose_;
00301
00303 struct GripperState{
00304 GripperState() : on_(false), view_facing_(false), edit_control_(false), torso_frame_(false) {}
00305
00306 bool on_;
00307 bool view_facing_;
00308 bool edit_control_;
00309 bool torso_frame_;
00310 };
00311
00313 struct ControlState{
00314 ControlState() : posture_r_(false), posture_l_(false), torso_on_(false), head_on_(false),
00315 projector_on_(false), init_head_goal_(false), base_on_(false) {}
00316
00317 void print()
00318 {
00319 ROS_DEBUG_NAMED("control_state", "gripper: on[%d|%d][%d], edit[%d|%d][%d], torso[%d|%d]",
00320 l_gripper_.on_, r_gripper_.on_, dual_grippers_.on_, l_gripper_.edit_control_, r_gripper_.edit_control_, dual_grippers_.edit_control_, l_gripper_.torso_frame_, r_gripper_.torso_frame_);
00321 ROS_DEBUG_NAMED("control_state", "posture[%d|%d] torso[%d] base[%d] head[%d] projector[%d]",
00322 posture_l_, posture_r_, torso_on_, base_on_, head_on_, projector_on_ );
00323 }
00324
00325 bool posture_r_;
00326 bool posture_l_;
00327 bool torso_on_;
00328 bool head_on_;
00329 bool projector_on_;
00330 bool init_head_goal_;
00331 bool base_on_;
00332 bool planar_only_;
00333 GripperState dual_grippers_;
00334 GripperState r_gripper_;
00335 GripperState l_gripper_;
00336 };
00337
00338 ControlState control_state_;
00339 pr2_wrappers::GripperController gripper_client_;
00340 pr2_wrappers::TorsoClient torso_client_;
00341 pr2_wrappers::BaseClient base_client_;
00342 pr2_wrappers::TuckArmsClient tuck_arms_client_;
00343
00344 boost::mutex planner_lock_;
00345
00346 object_manipulator::MechanismInterface mechanism_;
00347
00348 bool use_state_validator_;
00349 bool use_right_arm_;
00350 bool use_left_arm_;
00351 double gripper_control_linear_deadband_, gripper_control_angular_deadband_;
00352 double update_period_;
00353 double cartesian_clip_distance_;
00354 double cartesian_clip_angle_;
00355
00356 double max_direct_nav_radius_;
00357
00358 bool in_collision_r_, in_collision_l_;
00359
00360 boost::shared_ptr< boost::thread > sys_thread_;
00361
00363 object_manipulator::ServiceWrapper<arm_navigation_msgs::GetStateValidity> check_state_validity_client_;
00364 object_manipulator::ServiceWrapper<std_srvs::Empty> collider_node_reset_srv_;
00365 CloudHandler snapshot_client_;
00366 CloudHandler object_cloud_left_;
00367 CloudHandler object_cloud_right_;
00368
00370 ros::Subscriber object_cloud_left_sub_;
00371 ros::Subscriber object_cloud_right_sub_;
00372
00374 object_manipulator::ActionWrapper<pr2_object_manipulation_msgs::GetNavPoseAction> base_pose_client_;
00375
00377 object_manipulator::ActionWrapper<pr2_object_manipulation_msgs::GetGripperPoseAction> gripper_pose_client_;
00378
00380 int interface_number_;
00382 int task_number_;
00383
00384 std::string head_pointing_frame_;
00385
00387 std::string move_base_node_name_;
00388
00390 bool using_3d_nav_;
00391
00392
00393 bool alignedOdomValid_;
00394 boost::thread alignedOdomThread_;
00395 boost::mutex alignedOdomMutex_;
00396 tf::StampedTransform alignedOdom_;
00397
00399
00400 std::string l_gripper_type_, r_gripper_type_;
00401
00402 void publishAlignedOdom() {
00403 while ( true ) {
00404 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
00405 {
00406 boost::mutex::scoped_lock lock(alignedOdomMutex_);
00407 if ( alignedOdomValid_ ) {
00408 alignedOdom_.stamp_ = ros::Time::now();
00409 tfb_.sendTransform(alignedOdom_);
00410 }
00411 }
00412 }
00413 }
00414
00415 };
00416
00417
00418