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_plugs_actions/align_base.h"
00038
00039 using namespace ros;
00040 using namespace std;
00041
00042 static const string fixed_frame = "odom_combined";
00043
00044
00045 namespace pr2_plugs_actions{
00046
00047 AlignBaseAction::AlignBaseAction() :
00048 wall_detector_("detect_wall_norm", true),
00049 move_base_omnidirectional_("move_base_omnidirectional", true),
00050 action_server_(ros::NodeHandle(),
00051 "align_base",
00052 boost::bind(&AlignBaseAction::execute, this, _1))
00053 {
00054 ROS_INFO("Waiting for action servers");
00055 wall_detector_.waitForServer();
00056 move_base_omnidirectional_.waitForServer();
00057 };
00058
00059
00060 AlignBaseAction::~AlignBaseAction()
00061 {};
00062
00063
00064 void AlignBaseAction::execute(const pr2_plugs_msgs::AlignBaseGoalConstPtr& goal)
00065 {
00066 ROS_INFO("AlignBaseAction: execute");
00067
00068
00069 pr2_plugs_msgs::DetectWallNormGoal wall_norm_goal;
00070 wall_norm_goal.look_point = goal->look_point;
00071 wall_norm_goal.look_point.point.y = -fabs(goal->desired_distance);
00072 while (ros::ok() && wall_detector_.sendGoalAndWait(wall_norm_goal, ros::Duration(100.0), ros::Duration(5.0)) != actionlib::SimpleClientGoalState::SUCCEEDED)
00073 ROS_INFO("AlignBaseAction: try again to get wall norm");
00074
00075
00076 geometry_msgs::PointStamped wall_point_msg = wall_detector_.getResult()->wall_point;
00077 geometry_msgs::Vector3Stamped wall_norm_msg = wall_detector_.getResult()->wall_norm;
00078 if (!tf_.waitForTransform(fixed_frame, wall_norm_msg.header.frame_id, wall_norm_msg.header.stamp, ros::Duration(2.0))){
00079 ROS_ERROR("AlignBaseAction: failed to transform from frame %s to %s", fixed_frame.c_str(), wall_norm_msg.header.frame_id.c_str());
00080 action_server_.setAborted();
00081 return;
00082 }
00083 tf_.transformPoint(fixed_frame, wall_point_msg, wall_point_msg);
00084 tf_.transformVector(fixed_frame, wall_norm_msg, wall_norm_msg);
00085 tf::Vector3 wall_norm = fromVector(wall_norm_msg.vector);
00086 tf::Vector3 wall_point = fromPoint(wall_point_msg.point);
00087 ROS_INFO("AlignBaseAction: wall norm %f %f %f", wall_norm.x(), wall_norm.y(), wall_norm.z());
00088 ROS_INFO("AlignBaseAction: wall point %f %f %f", wall_point.x(), wall_point.y(), wall_point.z());
00089
00090
00091 if (fabs(wall_norm.z()) > 0.3){
00092 ROS_ERROR("A wall should be vertical. This vector (%f, %f, %f) is not vertical", wall_norm.x(), wall_norm.y(), wall_norm.z());
00093 action_server_.setAborted();
00094 return;
00095 }
00096
00097
00098 tf::StampedTransform robot_pose;
00099 if (!tf_.waitForTransform(fixed_frame, "base_link", ros::Time(), ros::Duration(2.0))){
00100 ROS_ERROR("AlignBaseAction: failed to transform from frame %s to base_link", fixed_frame.c_str());
00101 action_server_.setAborted();
00102 return;
00103 }
00104 tf_.lookupTransform(fixed_frame, "base_link", ros::Time(), robot_pose);
00105 ROS_INFO("AlignBaseAction: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(), tf::getYaw(robot_pose.getRotation()));
00106
00107
00108 tf::Pose desired_pose;
00109 desired_pose.setOrigin(robot_pose.getOrigin() + (wall_norm * (wall_norm.dot(wall_point-robot_pose.getOrigin()) - goal->desired_distance)));
00110 desired_pose.setRotation(tf::createQuaternionFromYaw(getVectorAngle(tf::Vector3(0,1,0), wall_norm*-1)));
00111 desired_pose = desired_pose * tf::Pose(tf::Quaternion::getIdentity(), tf::Vector3(goal->offset, 0.0, 0.0));
00112 ROS_INFO("AlignBaseAction: desired robot pose %f %f ==> %f", desired_pose.getOrigin().x(), desired_pose.getOrigin().y(), tf::getYaw(desired_pose.getRotation()));
00113
00114
00115 move_base_msgs::MoveBaseGoal move_base_goal;
00116 tf::poseStampedTFToMsg(tf::Stamped<tf::Pose>(desired_pose, ros::Time::now(), fixed_frame), move_base_goal.target_pose);
00117 if (move_base_omnidirectional_.sendGoalAndWait(move_base_goal, ros::Duration(20.0), ros::Duration(5.0)) != actionlib::SimpleClientGoalState::SUCCEEDED){
00118 ROS_ERROR("AlignBaseAction: failed to move base to desired pose");
00119 action_server_.setAborted();
00120 return;
00121 }
00122 pr2_plugs_msgs::AlignBaseResult align_result;
00123 align_result.base_pose = move_base_goal.target_pose;
00124 align_result.wall_norm = wall_norm_msg;
00125 action_server_.setSucceeded(align_result);
00126 }
00127
00128
00129
00130 geometry_msgs::Point AlignBaseAction::toPoint(const tf::Vector3& pnt)
00131 {
00132 geometry_msgs::Point res;
00133 res.x = pnt.x();
00134 res.y = pnt.y();
00135 res.z = pnt.z();
00136 return res;
00137 }
00138
00139 geometry_msgs::Vector3 AlignBaseAction::toVector(const tf::Vector3& pnt)
00140 {
00141 geometry_msgs::Vector3 res;
00142 res.x = pnt.x();
00143 res.y = pnt.y();
00144 res.z = pnt.z();
00145 return res;
00146 }
00147
00148 tf::Vector3 AlignBaseAction::fromVector(const geometry_msgs::Vector3& pnt)
00149 {
00150 return tf::Vector3(pnt.x, pnt.y, pnt.z);
00151 }
00152
00153 tf::Vector3 AlignBaseAction::fromPoint(const geometry_msgs::Point& pnt)
00154 {
00155 return tf::Vector3(pnt.x, pnt.y, pnt.z);
00156 }
00157
00158
00159 double AlignBaseAction::getVectorAngle(const tf::Vector3& v1, const tf::Vector3& v2)
00160 {
00161 tf::Vector3 vec1 = v1; vec1 = vec1.normalize();
00162 tf::Vector3 vec2 = v2; vec2 = vec2.normalize();
00163 double dot = vec2.x() * vec1.x() + vec2.y() * vec1.y();
00164 double perp_dot = vec2.y() * vec1.x() - vec2.x() * vec1.y();
00165 return atan2(perp_dot, dot);
00166 }
00167
00168 }
00169
00170
00171
00172 int main(int argc, char** argv)
00173 {
00174 ros::init(argc, argv, "align_base");
00175
00176 pr2_plugs_actions::AlignBaseAction action_server;
00177
00178 ros::spin();
00179 return 0;
00180 }