uos_freespace.cpp
Go to the documentation of this file.
1 /*
2  * uos_freespace
3  * Author: Marat "Peter" Purnyn
4  * Created 11/8/2015 (based on earlier work uos-freespace.cc)
5  */
7 #include <cmath>
8 #include <cstdio>
9 #include <geometry_msgs/Twist.h>
10 #include <geometry_msgs/QuaternionStamped.h>
11 
12 #define EPSILON 0.000001 // arbitrarily small value for cos limit to prevent numerical instability
13 #define min(a,b) ((a)<(b)?(a):(b)) //carried over from old code, possible cmath is enough
14 #define max(a,b) ((a)>(b)?(a):(b))
15 #define LASERSCAN_OPENING_ANGLE_WIDTH 270 //the viewing angle of the laserscanner (possibly only for lms100)
16 #define LASERSCAN_DEADZONE 45 //the angle range one either side of the scanner to ignore
17 
19  turn_state_(0),
20  scanner_orientation_(0),
21  turn_omega_(0),
22  private_nh_("~")
23 {
24  //sets the limits for the speed of the navigation
25  private_nh_.param("max_vel_x_", max_vel_x_, 0.5);
26  private_nh_.param("max_rotational_vel_", max_rotational_vel_, 0.3);
27 
28  //set tf_prefix
30 
31  turn_state_ = 0;
32 
34 
35  //publishers and subscribers
36  vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
38  ROS_DEBUG("constructor");
39 }
40 
41 double FreeSpace::calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan){
42  unsigned int i; //index of a laserscan point
43  double phi; //angle of i
44  double sinSum = 0.0, cosSum = 0.0;
45  double orientationWeight;
46  double alpha = 0.0;
47 
48  for (i = 0; i < laserscan->ranges.size(); i++) {
49  if(laserscan->ranges[i] > 0.1){
50  phi = laserscan->angle_min + i * laserscan->angle_increment;
51 
52  //the arg of cos should not be smaller than phi/2 otherwise
53  //the robot will be unstable when obstacles are close to its side.
54  //The exponential function is used to weight the range information.
55  //The farther an object is the larger its weight.
56 
57  orientationWeight = cos(phi/2) * 1.0/(1.0+exp(-(laserscan->ranges[i]-1)/0.5));
58  sinSum += sin(phi) * orientationWeight;
59  cosSum += cos(phi) * orientationWeight;
60  }
61  }
62  if (fabs(cosSum) > EPSILON){
63  alpha = atan2(sinSum, cosSum);
64  }
65  return alpha;
66 }
67 
68 int FreeSpace::isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan){
69  // To account for lasers that are mounted upside-down, we determine the
70  // min, max, and increment angles of the laser in the base frame.
72  q.setRPY(0.0, 0.0, laserscan->angle_min);
73  tf::Stamped<tf::Quaternion> min_q(q, laserscan->header.stamp,laserscan->header.frame_id);
74  q.setRPY(0.0, 0.0, laserscan->angle_max);
75  tf::Stamped<tf::Quaternion> max_q(q, laserscan->header.stamp,laserscan->header.frame_id);
76 
77  std::string base_link_frame = tf::resolve(tf_prefix_, "base_link");
78  std::string laser_frame = tf::resolve(tf_prefix_, "laser");
79 
80  try {
81  //wait for the tf frames to be available then transform the laserscan frame to the base frame
82  //this makes it so all scanners data is read as right-side up
83  tf_.waitForTransform(base_link_frame, laser_frame, laserscan->header.stamp, ros::Duration(1.0));
84  tf_.transformQuaternion(base_link_frame, min_q, min_q);
85  tf_.transformQuaternion(base_link_frame, max_q, max_q);
86  }
87  catch(tf::TransformException& e) {
88  //if there is an error transforming, keep the orientation unset to try again
89  ROS_WARN("Unable to transform min/max laser angles into base frame: %s",e.what());
90  return 0;
91  }
92 
93  ROS_DEBUG("Successfully transformed min/max laser angles into base frame");
94 
95  //calculate the angle increment of the scan with respect the base frame
96  double minAngle = tf::getYaw(min_q);
97  double maxAngle = tf::getYaw(max_q);
98  double baseFrameAngleIncrement = (maxAngle - minAngle) / laserscan->ranges.size();
99 
100  ROS_DEBUG("Laser angles in base frame: min: %.3f max: %.3f inc: %.3f", minAngle, maxAngle, baseFrameAngleIncrement);
101  if (baseFrameAngleIncrement < 0){
102  //upside-down
103  ROS_DEBUG("Inverting scan");
104  return -1;
105  }
106  return 1; //if not return by now, then assume right side up
107 }
108 
110  const sensor_msgs::LaserScan::ConstPtr &laserscan,
111  double xregion, double yregion,
112  int *indexOfObstacle,
113  double *distanceToObstacle)
114 {
115  unsigned int i; //index of laser point
116  double generalDistance = 65536.0; //starting max distance
117  *distanceToObstacle = 65536.0; //starting distance to obstacle
118  *indexOfObstacle = -1; //starting index of obstacle
119 
120  //calculate the number of laserpoints in the deadzone
121  int deadzonePoints = int(floor((((LASERSCAN_DEADZONE)*(M_PI/180))/laserscan->angle_increment)));
122  ROS_WARN("deadzonepoints :%d", deadzonePoints);
123  //The laser scanner detects part of the robot frame.
124  //ignore laserpoints in deadzone on the left and right of the scan
125  for (i = fabs(deadzonePoints); i < (laserscan->ranges.size() - fabs(deadzonePoints)); i++) {
126  if(laserscan->ranges[i] > 0.1){
127  double x = laserscan->ranges[i] * cos(laserscan->angle_min + i * laserscan->angle_increment);
128  double y = laserscan->ranges[i] * sin(laserscan->angle_min + i * laserscan->angle_increment);
129  if ((x < xregion) && (fabs(y) < (yregion / 2))) {
130  // Is there something in the region in front of the robot?
131  if (*distanceToObstacle > x) {
132  //Found obstacle, record distance and index
133  *distanceToObstacle = x;
134  *indexOfObstacle = i;
135  ROS_WARN("set index to obstacle %d", i);
136  }
137  } //is there something in the generel direction?
138  if ((x > xregion) && (fabs(y) < (yregion / 2))) {
139  //Is there something ahead of the robot?
140  if (generalDistance > x) {
141  //Set general distance to the closest object infront of the robot
142  generalDistance = x;
143  //ROS_WARN("set general distance");
144  }
145  }
146  }
147  }
148 
149  if (*indexOfObstacle == -1){
150  //There is no obstacle, so reset the distance.
151  *distanceToObstacle = generalDistance;
152  }
153  ROS_WARN("distance to obstacle :%f", *distanceToObstacle);
154  ROS_WARN(" index obstacle :%d", *indexOfObstacle);
155  return 0;
156 }
157 
158 // Statemachine
159 // Drive into the general direction of the freespace infront of the Robot
160 // If there is an obstacle infront of the robot turn away from it
161 // X axis is pointing forward
162 // Y axis is pointing left
163 // Z axis is pointing up
164 void FreeSpace::autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan){
165  ROS_DEBUG("autonomousBehaviour");
166  // region is a quadilatiral in front of the robot
167  // define the size
168  double xregion = 0.5; // x is in forward
169  double yregion = 0.5; // y is left
170  double DTOStopTurning = 1.0; // defines when to start to turn into freespace
171  double DTOStartTurning = 0.5; // defines when to start to turn away form an obstacle
172  int indexOfObstacle = -1;
173  double frontMaxDistance = 0;
174 
175  double uTurning = 0.2 * max_vel_x_; //decrease the speed while turning
176  double distanceToObstacle = INFINITY;
177  double omega = calcFreespace(laserscan); // find the freespace infront of the robot and return the angle to the direction of the freespace
178  double u = max_vel_x_; // define maximum velocity of the robot
179 
180  //ROS_WARN("behave maxpoints :%d", laserscan->ranges.size());
181 
182  for(unsigned int i = 0; i < laserscan->ranges.size(); i++) {
183  if(laserscan->ranges[i] > frontMaxDistance) {
184  frontMaxDistance = laserscan->ranges[i];
185  }
186  }
187 
188  if(scanner_orientation_ == 0) {
190  ROS_DEBUG("scanner_orientation_: %d", scanner_orientation_);
191  }
192 
193  // look for obstacles infront of the robot
194  checkRange(laserscan,xregion,yregion,&indexOfObstacle,&distanceToObstacle);
195 
196  // slow down if obstacle
197  if (indexOfObstacle != -1) {
198  u = max(distanceToObstacle - 0.2 / (xregion * max_vel_x_),0);
199  }
200 
201  // handle turning mode
202  // turn if obstacle is infront
203  if (turn_state_ == 1) {
204  ROS_WARN("turn_state: 1");
205  if ( (distanceToObstacle > DTOStopTurning)) {
206  turn_state_ = 0; // end turning
207  }
208  else {
209  //turn slower if obstacle is infront
210  ROS_WARN("turning away");
211  }
212  u = min(u, uTurning); //set velocity to u if its not higher then the maximum velocity
213  }
214  // detect end of corridor use StopTurn val
215  if (((frontMaxDistance < DTOStopTurning) || (distanceToObstacle < DTOStartTurning)) && (turn_state_ == 0) ) {
216  // start turning
217  // turn away from obstacle
218  if (indexOfObstacle > laserscan->ranges.size() / 2) {
220  //omega = min(omega,max_rotational_vel_); //omega should not exceed max_rotational_vel_
221  ROS_WARN("turning_left");
222  }
223  else if (indexOfObstacle <= laserscan->ranges.size() / 2 && indexOfObstacle >= 0) {
225 
226  //omega = max(omega,-max_rotational_vel_);
227  ROS_WARN("turning_right");
228  }
229  turn_state_ = 1;
230  u = min(u, uTurning);
231  }
232  if (turn_state_ == 1){
233  omega = turn_omega_;
234  }
235 
236  geometry_msgs::Twist vel;
237  vel.linear.x = u;
238  vel.angular.z = scanner_orientation_ * omega;
239  vel_pub_.publish(vel);
240 }
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static double getYaw(const Quaternion &bt_q)
#define max(a, b)
int isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
ros::NodeHandle private_nh_
Definition: uos_freespace.h:24
#define min(a, b)
std::string tf_prefix_
Definition: uos_freespace.h:21
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
double turn_omega_
Definition: uos_freespace.h:17
std::string resolve(const std::string &prefix, const std::string &frame_name)
ros::NodeHandle nh_
Definition: uos_freespace.h:23
void transformQuaternion(const std::string &target_frame, const geometry_msgs::QuaternionStamped &stamped_in, geometry_msgs::QuaternionStamped &stamped_out) const
int scanner_orientation_
Definition: uos_freespace.h:20
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
double max_rotational_vel_
Definition: uos_freespace.h:16
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformListener tf_
Definition: uos_freespace.h:30
#define LASERSCAN_DEADZONE
ros::Subscriber laser_sub_
Definition: uos_freespace.h:28
#define EPSILON
double max_vel_x_
Definition: uos_freespace.h:16
void autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan)
int turn_state_
Definition: uos_freespace.h:18
ros::Publisher vel_pub_
Definition: uos_freespace.h:26
int checkRange(const sensor_msgs::LaserScan::ConstPtr &laserscan, double xregion, double yregion, int *indexToObstacle, double *distanceToObstacle)
double calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan)
#define ROS_DEBUG(...)


uos_freespace
Author(s): Jochen Sprickerhof
autogenerated on Mon Jun 10 2019 15:49:30