00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include "pr2_doors_common/door_functions.h"
00038 #include "pr2_doors_actions/action_open_door.h"
00039
00040
00041 using namespace tf;
00042 using namespace KDL;
00043 using namespace ros;
00044 using namespace std;
00045 using namespace door_handle_detector;
00046 using namespace pr2_doors_common;
00047 using namespace actionlib;
00048
00049 static const string fixed_frame = "odom_combined";
00050
00051
00052 OpenDoorAction::OpenDoorAction(tf::TransformListener& tf) :
00053 tf_(tf),
00054 action_server_(ros::NodeHandle(),
00055 "open_door",
00056 boost::bind(&OpenDoorAction::execute, this, _1))
00057 {
00058 ros::NodeHandle node;
00059 tff_pub_ = node.advertise<tff_controller::TaskFrameFormalism>("r_arm_cartesian_tff_controller/command", 10);
00060 };
00061
00062
00063
00064 OpenDoorAction::~OpenDoorAction()
00065 {};
00066
00067
00068
00069 void OpenDoorAction::execute(const door_msgs::DoorGoalConstPtr& goal)
00070 {
00071 ROS_INFO("OpenDoorAction: execute");
00072
00073
00074 tff_door_.mode.linear.x = tff_door_.VELOCITY;
00075 tff_door_.mode.linear.y = tff_door_.FORCE;
00076 tff_door_.mode.linear.z = tff_door_.FORCE;
00077 tff_door_.mode.angular.x = tff_door_.FORCE;
00078 tff_door_.mode.angular.y = tff_door_.FORCE;
00079 tff_door_.mode.angular.z = tff_door_.POSITION;
00080
00081 tff_door_.value.linear.x = getDoorDir(goal->door) * 0.45;
00082 tff_door_.value.linear.y = 0.0;
00083 tff_door_.value.linear.z = 0.0;
00084 tff_door_.value.angular.x = 0.0;
00085 tff_door_.value.angular.y = 0.0;
00086 tff_door_.value.angular.z = 0.0;
00087
00088
00089 while (ros::ok() && !action_server_.isPreemptRequested()){
00090 tff_pub_.publish(tff_door_);
00091 Duration(0.1).sleep();
00092 }
00093
00094
00095 ROS_INFO("ActionOpenDoor: Preempted");
00096
00097 action_server_.setPreempted();
00098 }
00099