Public Member Functions | Public Attributes
nj_oa_laser::TwistHandler Class Reference

#include <twist_handler.h>

List of all members.

Public Member Functions

geometry_msgs::Twist getTwist (const sensor_msgs::LaserScan &scan)
 TwistHandler (const double robot_radius)

Public Attributes

double force_turn_left_factor
double long_distance
 (m), if no obstacle within this distance, go straight.
double long_lateral_distance
 If no obstacle within this lateral distance, go straight (m).
double max_angular_velocity
 Max angular velocity around z (rad/s).
double max_linear_velocity
 Linear velocity in x-direction without obstacle (m/s).
double min_distance
 (m), if an obstacle is closer (y-direction) than this, turn and don't go forward.
double robot_radius
 (m), robot radius.
double short_lateral_distance
 If obstacle within this lateral distance, turn and don't go forward (m)
double turnrate_collide
 (rad/s), turn rate when obstacle closer than min_distance.
double turnrate_factor
double vel_close_obstacle
 (m/s), linear velocity if obstacle between min_distance and long_distance.

Detailed Description

Definition at line 14 of file twist_handler.h.


Constructor & Destructor Documentation

nj_oa_laser::TwistHandler::TwistHandler ( const double  robot_radius)

Definition at line 8 of file twist_handler.cpp.


Member Function Documentation

geometry_msgs::Twist nj_oa_laser::TwistHandler::getTwist ( const sensor_msgs::LaserScan &  scan)

Return the twist to avoid obstacles

The algorithm considers only beams in [-pi, pi]. The robot will turn in the direction where the mean obstacle distance is larger. The algorithm has 4 behaviors:

  • if the robot is in a corner (mean distance in front < 2 collide distance), turn left.
  • if obstacles are close (collide distance), only turn towards free space.
  • if obstacles are close but farther than the collide distance, go forward and turn proportionnally to the mean side distance to obstacles.
  • if obstacles are far, go strictly forward.

Definition at line 34 of file twist_handler.cpp.


Member Data Documentation

If the mean obstacle distance is smaller that this factor times min_distance, force a left turn to avoid oscillating in front of a corner.

Definition at line 27 of file twist_handler.h.

(m), if no obstacle within this distance, go straight.

Definition at line 24 of file twist_handler.h.

If no obstacle within this lateral distance, go straight (m).

Definition at line 26 of file twist_handler.h.

Max angular velocity around z (rad/s).

Definition at line 35 of file twist_handler.h.

Linear velocity in x-direction without obstacle (m/s).

Definition at line 34 of file twist_handler.h.

(m), if an obstacle is closer (y-direction) than this, turn and don't go forward.

Definition at line 23 of file twist_handler.h.

(m), robot radius.

Definition at line 22 of file twist_handler.h.

If obstacle within this lateral distance, turn and don't go forward (m)

Definition at line 25 of file twist_handler.h.

(rad/s), turn rate when obstacle closer than min_distance.

Definition at line 30 of file twist_handler.h.

(rad.m^-1.s^-1, > 0), if obstacle closer than long_distance, turnrate = -turnrate_factor * mean(lateral_position_of_obstacle).

Definition at line 32 of file twist_handler.h.

(m/s), linear velocity if obstacle between min_distance and long_distance.

Definition at line 31 of file twist_handler.h.


The documentation for this class was generated from the following files:


nj_oa_laser
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Thu Jun 6 2019 17:50:51