Go to the documentation of this file.00001 #include <math.h>
00002 #include <stdio.h>
00003 #include <ros/ros.h>
00004 #include <geometry_msgs/Twist.h>
00005 #include <sensor_msgs/LaserScan.h>
00006
00007 #define INVPIDIV180 57.29578
00008 #define EPSILON 0.000001 // vergleich von 2 doubles
00009 #define min(a,b) ((a)<(b)?(a):(b))
00010
00011 double max_vel_x, max_rotational_vel;
00012 ros::Publisher vel_pub;
00013
00014 double calc_freespace(const sensor_msgs::LaserScan::ConstPtr &laser)
00015 {
00016 unsigned int i;
00017 double phi;
00018 double sinsum = 0.0, cossum = 0.0;
00019 double orientation_weight;
00020 double alpha = 0.0;
00021
00022
00023
00024
00025 for (i = 0; i < laser->ranges.size(); i++) {
00026
00027
00028
00029
00030 phi = laser->angle_min + i * laser->angle_increment;
00031
00032
00033
00034
00035
00036
00037 orientation_weight = cos(phi/1.2) * 1.0/(1.0+exp(-(laser->ranges[i]-3.0)/0.3));
00038
00039
00040 sinsum += sin(phi) * orientation_weight;
00041 cossum += cos(phi) * orientation_weight;
00042 }
00043
00044
00045 if (fabs(sinsum) > EPSILON) alpha = atan2(sinsum, cossum);
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056 return alpha;
00057 }
00058
00059 int SICK_Check_range(const sensor_msgs::LaserScan::ConstPtr &laser,
00060 double xregion, double yregion,
00061 int *index_to_obstacle, double *distance_to_obstacle)
00062 {
00063 unsigned int i;
00064 double general_distance = 65536.0;
00065 *distance_to_obstacle = 65536.0;
00066 *index_to_obstacle = -1;
00067
00068 for (i = 10; i < (laser->ranges.size() - 10); i++) {
00069
00070
00071 double x = laser->ranges[i] * sin(laser->angle_min + i * laser->angle_increment);
00072 double y = laser->ranges[i] * cos(laser->angle_min + i * laser->angle_increment);
00073 if (laser->ranges[i] > 0.1) {
00074 if ((fabs(x) < xregion) && (y < yregion)) {
00075 if (*distance_to_obstacle > y) {
00076 *distance_to_obstacle = y;
00077 *index_to_obstacle = i;
00078 }
00079 }
00080 if ((fabs(x) < xregion)) {
00081 if (general_distance > y) {
00082 general_distance = y;
00083 }
00084 }
00085 }
00086 }
00087 if (*index_to_obstacle == -1) *distance_to_obstacle = general_distance;
00088 return 0;
00089 }
00090
00091 void autonomous_behave(const sensor_msgs::LaserScan::ConstPtr &laser)
00092 {
00093
00094 int state_turn = 0;
00095 double XRegion = 0.25;
00096 double ZRegion = 0.56;
00097 double DTOStopTurning = 0.60;
00098 double DTOStartTurning = 0.50;
00099 int index_to_obstacle = -1;
00100 double Front_Max_Distance = -1;
00101 double turn_omega = 0.0;
00102 double u_turning = 0.2 * max_vel_x;
00103 double distance_to_obstacle = INFINITY;
00104 double omega = calc_freespace(laser);
00105 double u = max_vel_x;
00106 for(unsigned int i = 0; i < laser->ranges.size(); i++) {
00107 if(laser->ranges[i] > Front_Max_Distance) {
00108 Front_Max_Distance = laser->ranges[i];
00109 }
00110 }
00111
00112
00113
00114 SICK_Check_range(laser,
00115 XRegion,
00116 ZRegion,
00117 &index_to_obstacle,
00118 &distance_to_obstacle);
00119
00120
00121 if (index_to_obstacle != -1) {
00122
00123 u = distance_to_obstacle / ZRegion * max_vel_x;
00124 }
00125
00126
00127 if (state_turn == 1) {
00128
00129 if ( (distance_to_obstacle > DTOStopTurning)
00130
00131 ) {
00132 state_turn = 0;
00133
00134 } else {
00135 omega = turn_omega;
00136 u = min(u, u_turning);
00137 }
00138 }
00139
00140 if (((Front_Max_Distance < DTOStopTurning)
00141 || (distance_to_obstacle < DTOStartTurning))
00142 && (state_turn == 0) ) {
00143
00144
00145
00146 if (omega > 0.0) {
00147 omega = 0.999 * M_PI;
00148 }
00149 if (omega < 0.0) {
00150 omega = -0.999 * M_PI;
00151 }
00152 state_turn = 1;
00153 turn_omega = omega;
00154 u = min(u, u_turning);
00155
00156 }
00157
00158
00159
00160 geometry_msgs::Twist vel;
00161 vel.linear.x = u;
00162 vel.angular.z = omega;
00163 vel_pub.publish(vel);
00164 }
00165
00166 int main(int argc, char** argv)
00167 {
00168 ros::init(argc, argv, "kurt_freespace");
00169
00170 ros::NodeHandle nh;
00171 ros::NodeHandle nh_ns("~");
00172
00173 nh_ns.param("max_vel_x", max_vel_x, 0.9);
00174 nh_ns.param("max_rotational_vel", max_rotational_vel, 1.0);
00175
00176 vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00177 ros::Subscriber laser_sub = nh.subscribe("scan", 10, autonomous_behave);
00178
00179 ros::spin();
00180 }