9 #include <geometry_msgs/Twist.h> 10 #include <geometry_msgs/QuaternionStamped.h> 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 20 scanner_orientation_(0),
44 double sinSum = 0.0, cosSum = 0.0;
45 double orientationWeight;
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;
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;
63 alpha = atan2(sinSum, cosSum);
72 q.
setRPY(0.0, 0.0, laserscan->angle_min);
74 q.
setRPY(0.0, 0.0, laserscan->angle_max);
89 ROS_WARN(
"Unable to transform min/max laser angles into base frame: %s",e.what());
93 ROS_DEBUG(
"Successfully transformed min/max laser angles into base frame");
98 double baseFrameAngleIncrement = (maxAngle - minAngle) / laserscan->ranges.size();
100 ROS_DEBUG(
"Laser angles in base frame: min: %.3f max: %.3f inc: %.3f", minAngle, maxAngle, baseFrameAngleIncrement);
101 if (baseFrameAngleIncrement < 0){
110 const sensor_msgs::LaserScan::ConstPtr &laserscan,
111 double xregion,
double yregion,
112 int *indexOfObstacle,
113 double *distanceToObstacle)
116 double generalDistance = 65536.0;
117 *distanceToObstacle = 65536.0;
118 *indexOfObstacle = -1;
121 int deadzonePoints = int(floor((((
LASERSCAN_DEADZONE)*(M_PI/180))/laserscan->angle_increment)));
122 ROS_WARN(
"deadzonepoints :%d", deadzonePoints);
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))) {
131 if (*distanceToObstacle > x) {
133 *distanceToObstacle = x;
134 *indexOfObstacle = i;
135 ROS_WARN(
"set index to obstacle %d", i);
138 if ((x > xregion) && (fabs(y) < (yregion / 2))) {
140 if (generalDistance > x) {
149 if (*indexOfObstacle == -1){
151 *distanceToObstacle = generalDistance;
153 ROS_WARN(
"distance to obstacle :%f", *distanceToObstacle);
154 ROS_WARN(
" index obstacle :%d", *indexOfObstacle);
168 double xregion = 0.5;
169 double yregion = 0.5;
170 double DTOStopTurning = 1.0;
171 double DTOStartTurning = 0.5;
172 int indexOfObstacle = -1;
173 double frontMaxDistance = 0;
176 double distanceToObstacle = INFINITY;
182 for(
unsigned int i = 0; i < laserscan->ranges.size(); i++) {
183 if(laserscan->ranges[i] > frontMaxDistance) {
184 frontMaxDistance = laserscan->ranges[i];
194 checkRange(laserscan,xregion,yregion,&indexOfObstacle,&distanceToObstacle);
197 if (indexOfObstacle != -1) {
198 u =
max(distanceToObstacle - 0.2 / (xregion *
max_vel_x_),0);
205 if ( (distanceToObstacle > DTOStopTurning)) {
212 u =
min(u, uTurning);
215 if (((frontMaxDistance < DTOStopTurning) || (distanceToObstacle < DTOStartTurning)) && (
turn_state_ == 0) ) {
218 if (indexOfObstacle > laserscan->ranges.size() / 2) {
223 else if (indexOfObstacle <= laserscan->ranges.size() / 2 && indexOfObstacle >= 0) {
230 u =
min(u, uTurning);
236 geometry_msgs::Twist vel;
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)
int isInvertedScannerCheck(const sensor_msgs::LaserScan::ConstPtr &laserscan)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::NodeHandle private_nh_
std::string resolve(const std::string &prefix, const std::string &frame_name)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
double max_rotational_vel_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformListener tf_
#define LASERSCAN_DEADZONE
ros::Subscriber laser_sub_
void autonomousBehaviour(const sensor_msgs::LaserScan::ConstPtr &laserscan)
int checkRange(const sensor_msgs::LaserScan::ConstPtr &laserscan, double xregion, double yregion, int *indexToObstacle, double *distanceToObstacle)
double calcFreespace(const sensor_msgs::LaserScan::ConstPtr &laserscan)