00001
00002
00003
00004
00005
00006 #include <uos_freespace/uos_freespace.h>
00007 #include <cmath>
00008 #include <cstdio>
00009 #include <geometry_msgs/Twist.h>
00010 #include <geometry_msgs/QuaternionStamped.h>
00011
00012 #define EPSILON 0.000001 // arbitrarily small value for cos limit to prevent numerical instability
00013 #define min(a,b) ((a)<(b)?(a):(b)) //carried over from old code, possible cmath is enough
00014 #define max(a,b) ((a)>(b)?(a):(b))
00015 #define LASERSCAN_OPENING_ANGLE_WIDTH 270 //the viewing angle of the laserscanner (possibly only for lms100)
00016 #define LASERSCAN_DEADZONE 45 //the angle range one either side of the scanner to ignore
00017
00018 FreeSpace::FreeSpace():
00019 turn_state_(0),
00020 scanner_orientation_(0),
00021 turn_omega_(0),
00022 private_nh_("~")
00023 {
00024
00025 private_nh_.param("max_vel_x_", max_vel_x_, 0.5);
00026 private_nh_.param("max_rotational_vel_", max_rotational_vel_, 0.3);
00027
00028
00029 tf_prefix_ = tf::getPrefixParam(private_nh_);
00030
00031 turn_state_ = 0;
00032
00033 scanner_orientation_ = 0;
00034
00035
00036 vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00037 laser_sub_ = nh_.subscribe("scan", 10, &FreeSpace::autonomousBehaviour, this);
00038 ROS_DEBUG("constructor");
00039 }
00040
00041 double FreeSpace::calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan){
00042 unsigned int i;
00043 double phi;
00044 double sinSum = 0.0, cosSum = 0.0;
00045 double orientationWeight;
00046 double alpha = 0.0;
00047
00048 for (i = 0; i < laserscan->ranges.size(); i++) {
00049 if(laserscan->ranges[i] > 0.1){
00050 phi = laserscan->angle_min + i * laserscan->angle_increment;
00051
00052
00053
00054
00055
00056
00057 orientationWeight = cos(phi/2) * 1.0/(1.0+exp(-(laserscan->ranges[i]-1)/0.5));
00058 sinSum += sin(phi) * orientationWeight;
00059 cosSum += cos(phi) * orientationWeight;
00060 }
00061 }
00062 if (fabs(cosSum) > EPSILON){
00063 alpha = atan2(sinSum, cosSum);
00064 }
00065 return alpha;
00066 }
00067
00068 int FreeSpace::isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan){
00069
00070
00071 tf::Quaternion q;
00072 q.setRPY(0.0, 0.0, laserscan->angle_min);
00073 tf::Stamped<tf::Quaternion> min_q(q, laserscan->header.stamp,laserscan->header.frame_id);
00074 q.setRPY(0.0, 0.0, laserscan->angle_max);
00075 tf::Stamped<tf::Quaternion> max_q(q, laserscan->header.stamp,laserscan->header.frame_id);
00076
00077 std::string base_link_frame = tf::resolve(tf_prefix_, "base_link");
00078 std::string laser_frame = tf::resolve(tf_prefix_, "laser");
00079
00080 try {
00081
00082
00083 tf_.waitForTransform(base_link_frame, laser_frame, laserscan->header.stamp, ros::Duration(1.0));
00084 tf_.transformQuaternion(base_link_frame, min_q, min_q);
00085 tf_.transformQuaternion(base_link_frame, max_q, max_q);
00086 }
00087 catch(tf::TransformException& e) {
00088
00089 ROS_WARN("Unable to transform min/max laser angles into base frame: %s",e.what());
00090 return 0;
00091 }
00092
00093 ROS_DEBUG("Successfully transformed min/max laser angles into base frame");
00094
00095
00096 double minAngle = tf::getYaw(min_q);
00097 double maxAngle = tf::getYaw(max_q);
00098 double baseFrameAngleIncrement = (maxAngle - minAngle) / laserscan->ranges.size();
00099
00100 ROS_DEBUG("Laser angles in base frame: min: %.3f max: %.3f inc: %.3f", minAngle, maxAngle, baseFrameAngleIncrement);
00101 if (baseFrameAngleIncrement < 0){
00102
00103 ROS_DEBUG("Inverting scan");
00104 return -1;
00105 }
00106 return 1;
00107 }
00108
00109 int FreeSpace::checkRange(
00110 const sensor_msgs::LaserScan::ConstPtr &laserscan,
00111 double xregion, double yregion,
00112 int *indexOfObstacle,
00113 double *distanceToObstacle)
00114 {
00115 unsigned int i;
00116 double generalDistance = 65536.0;
00117 *distanceToObstacle = 65536.0;
00118 *indexOfObstacle = -1;
00119
00120
00121 int deadzonePoints = int(floor((((LASERSCAN_DEADZONE)*(M_PI/180))/laserscan->angle_increment)));
00122 ROS_WARN("deadzonepoints :%d", deadzonePoints);
00123
00124
00125 for (i = fabs(deadzonePoints); i < (laserscan->ranges.size() - fabs(deadzonePoints)); i++) {
00126 if(laserscan->ranges[i] > 0.1){
00127 double x = laserscan->ranges[i] * cos(laserscan->angle_min + i * laserscan->angle_increment);
00128 double y = laserscan->ranges[i] * sin(laserscan->angle_min + i * laserscan->angle_increment);
00129 if ((x < xregion) && (fabs(y) < (yregion / 2))) {
00130
00131 if (*distanceToObstacle > x) {
00132
00133 *distanceToObstacle = x;
00134 *indexOfObstacle = i;
00135 ROS_WARN("set index to obstacle %d", i);
00136 }
00137 }
00138 if ((x > xregion) && (fabs(y) < (yregion / 2))) {
00139
00140 if (generalDistance > x) {
00141
00142 generalDistance = x;
00143
00144 }
00145 }
00146 }
00147 }
00148
00149 if (*indexOfObstacle == -1){
00150
00151 *distanceToObstacle = generalDistance;
00152 }
00153 ROS_WARN("distance to obstacle :%f", *distanceToObstacle);
00154 ROS_WARN(" index obstacle :%d", *indexOfObstacle);
00155 return 0;
00156 }
00157
00158
00159
00160
00161
00162
00163
00164 void FreeSpace::autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan){
00165 ROS_DEBUG("autonomousBehaviour");
00166
00167
00168 double xregion = 0.5;
00169 double yregion = 0.5;
00170 double DTOStopTurning = 1.0;
00171 double DTOStartTurning = 0.5;
00172 int indexOfObstacle = -1;
00173 double frontMaxDistance = 0;
00174
00175 double uTurning = 0.2 * max_vel_x_;
00176 double distanceToObstacle = INFINITY;
00177 double omega = calcFreespace(laserscan);
00178 double u = max_vel_x_;
00179
00180
00181
00182 for(unsigned int i = 0; i < laserscan->ranges.size(); i++) {
00183 if(laserscan->ranges[i] > frontMaxDistance) {
00184 frontMaxDistance = laserscan->ranges[i];
00185 }
00186 }
00187
00188 if(scanner_orientation_ == 0) {
00189 scanner_orientation_ = isInvertedScannerCheck(laserscan);
00190 ROS_DEBUG("scanner_orientation_: %d", scanner_orientation_);
00191 }
00192
00193
00194 checkRange(laserscan,xregion,yregion,&indexOfObstacle,&distanceToObstacle);
00195
00196
00197 if (indexOfObstacle != -1) {
00198 u = max(distanceToObstacle - 0.2 / (xregion * max_vel_x_),0);
00199 }
00200
00201
00202
00203 if (turn_state_ == 1) {
00204 ROS_WARN("turn_state: 1");
00205 if ( (distanceToObstacle > DTOStopTurning)) {
00206 turn_state_ = 0;
00207 }
00208 else {
00209
00210 ROS_WARN("turning away");
00211 }
00212 u = min(u, uTurning);
00213 }
00214
00215 if (((frontMaxDistance < DTOStopTurning) || (distanceToObstacle < DTOStartTurning)) && (turn_state_ == 0) ) {
00216
00217
00218 if (indexOfObstacle > laserscan->ranges.size() / 2) {
00219 turn_omega_ = -max_rotational_vel_;
00220
00221 ROS_WARN("turning_left");
00222 }
00223 else if (indexOfObstacle <= laserscan->ranges.size() / 2 && indexOfObstacle >= 0) {
00224 turn_omega_ = max_rotational_vel_;
00225
00226
00227 ROS_WARN("turning_right");
00228 }
00229 turn_state_ = 1;
00230 u = min(u, uTurning);
00231 }
00232 if (turn_state_ == 1){
00233 omega = turn_omega_;
00234 }
00235
00236 geometry_msgs::Twist vel;
00237 vel.linear.x = u;
00238 vel.angular.z = scanner_orientation_ * omega;
00239 vel_pub_.publish(vel);
00240 }