Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes
NoCollisionAlgorithm Class Reference

IRI ROS Specific Driver Class. More...

#include <no_collision_alg.h>

List of all members.

Public Types

typedef
iri_no_collision::NoCollisionConfig 
Config
 define config type

Public Member Functions

void config_update (const Config &new_cfg, uint32_t level=0)
 config update
void getDistance2Goal (geometry_msgs::Pose &current_goal)
bool isGoalReached (void)
 goal is reached
bool isGoalTraversable (const sensor_msgs::LaserScan &laser, const geometry_msgs::Point &goal)
 goal traversable
void lock (void)
 Lock Algorithm.
bool movePlatform (const sensor_msgs::LaserScan &laser, const geometry_msgs::Pose &local_goal, geometry_msgs::Twist &twist)
 move platform
 NoCollisionAlgorithm (void)
 constructor
void setGoal (const geometry_msgs::Pose &local_goal)
 reset distance to goal
void setRotationalSpeed (const double vr)
void setTranslationalSpeed (const double vt)
bool try_enter (void)
 Tries Access to Algorithm.
void unlock (void)
 Unlock Algorithm.
 ~NoCollisionAlgorithm (void)
 Destructor.

Public Attributes

Config config_
 config variable

Protected Member Functions

void fromCartesian2Polar (const geometry_msgs::Point &p, float &module, float &angle)
 cartesian to polar conversion
void fromPolar2Cartesian (const float &module, const float &angle, geometry_msgs::Point &p)
void updateRotationTrajParams (void)
void updateTranslationTrajParams (void)

Protected Attributes

float acc_angle_
float acc_dist_
CMutex alg_mutex_
 define config type
float ANGLE_TOL_
float current_angle_
float current_dist_
ros::Time current_time_
float current_vr_
float current_vt_
float deacc_angle_
float deacc_dist_
float desired_vr_
float desired_vt_
float DIST_TOL_
float heading
float LASER_SAFE_DIST_
float MAX_ANGLE_TO_STOP_
float MIN_SAFE_ANGLE_
float MIN_SAFE_DISTANCE_
float OA_CONE_ANGLE_
float R_ACC_
float T_ACC_
float target_angle_
float target_dist_
float target_vr_
float target_vt_
float VR_MAX_
TrajStates vr_state_
float VT_MAX_
TrajStates vt_state_

Static Protected Attributes

static const float MIN_LASER_RANGE_ = 0.005f

Detailed Description

IRI ROS Specific Driver Class.

Definition at line 44 of file no_collision_alg.h.


Member Typedef Documentation

typedef iri_no_collision::NoCollisionConfig NoCollisionAlgorithm::Config

define config type

Define a Config type with the NoCollisionConfig. All driver implementations will then use the same variable type Config.

Definition at line 120 of file no_collision_alg.h.


Constructor & Destructor Documentation

constructor

In this constructor parameters related to the specific driver can be initalized. Those parameters can be also set in the openDriver() function. Attributes from the main node driver class IriBaseDriver such as loop_rate, may be also overload here.

Definition at line 7 of file no_collision_alg.cpp.

Destructor.

This destructor is called when the object is about to be destroyed.

Definition at line 45 of file no_collision_alg.cpp.


Member Function Documentation

void NoCollisionAlgorithm::config_update ( const Config new_cfg,
uint32_t  level = 0 
)

config update

In this function the driver parameters must be updated with the input config variable. Then the new configuration state will be stored in the Config attribute.

Parameters:
new_cfgthe new driver configuration state
levellevel in which the update is taken place

Definition at line 94 of file no_collision_alg.cpp.

void NoCollisionAlgorithm::fromCartesian2Polar ( const geometry_msgs::Point p,
float &  module,
float &  angle 
) [protected]

cartesian to polar conversion

This function converts a cartesian point into module and angle polar values.

Parameters:
pinput cartesian point
moduleoutput polar module
agnleoutput polar angle

Definition at line 49 of file no_collision_alg.cpp.

void NoCollisionAlgorithm::fromPolar2Cartesian ( const float &  module,
const float &  angle,
geometry_msgs::Point p 
) [protected]

Definition at line 55 of file no_collision_alg.cpp.

Definition at line 185 of file no_collision_alg.cpp.

goal is reached

This function returns true if the distance and angle to the requested goal are less than previously defined thresholds: MIN_SAFE_DISTANCE, MIN_SAFE_ANGLE.

Returns:
true if both distance and angle values are less than thresholds.

Definition at line 137 of file no_collision_alg.cpp.

bool NoCollisionAlgorithm::isGoalTraversable ( const sensor_msgs::LaserScan &  laser,
const geometry_msgs::Point goal 
)

goal traversable

This function returns true if any of the laser bins detects an obstacle (bin range is less than platform safety_distance).

Parameters:
lasercurrent laser scan
safety_distanceplatfom's safety/clear distance
Returns:
bool true if all laser bins are clear of obstacles

Definition at line 368 of file no_collision_alg.cpp.

void NoCollisionAlgorithm::lock ( void  ) [inline]

Lock Algorithm.

Locks access to the Algorithm class

Definition at line 145 of file no_collision_alg.h.

bool NoCollisionAlgorithm::movePlatform ( const sensor_msgs::LaserScan &  laser,
const geometry_msgs::Pose local_goal,
geometry_msgs::Twist &  twist 
)

move platform

This function computes appropiate Twist values to command a platform given a laser scan and a local pose goal. Distance and angle to goal are updated with respect the local pose goal. The isGoalTraversable function determines whether the goal is clear of obstacles or not. The Twist command is computed based on distance and angle to goal values.

Parameters:
scancurrent laser scan
local_goalrequested pose goal in local coordinates
Returns:
Twist linear and angular velocites to command the platform

Definition at line 191 of file no_collision_alg.cpp.

void NoCollisionAlgorithm::setGoal ( const geometry_msgs::Pose local_goal)

reset distance to goal

In this function distance and angle to goal are reset to default to ensure the new request will be tracked properly.

Definition at line 113 of file no_collision_alg.cpp.

void NoCollisionAlgorithm::setRotationalSpeed ( const double  vr)

Definition at line 165 of file no_collision_alg.cpp.

Definition at line 145 of file no_collision_alg.cpp.

Tries Access to Algorithm.

Tries access to Algorithm

Returns:
true if the lock was adquired, false otherwise

Definition at line 161 of file no_collision_alg.h.

void NoCollisionAlgorithm::unlock ( void  ) [inline]

Unlock Algorithm.

Unlocks access to the Algorithm class

Definition at line 152 of file no_collision_alg.h.

Definition at line 76 of file no_collision_alg.cpp.

Definition at line 61 of file no_collision_alg.cpp.


Member Data Documentation

Definition at line 87 of file no_collision_alg.h.

Definition at line 77 of file no_collision_alg.h.

define config type

Define a Config type with the NoCollisionConfig. All driver implementations will then use the same variable type Config.

Definition at line 53 of file no_collision_alg.h.

Definition at line 62 of file no_collision_alg.h.

config variable

This variable has all the driver parameters defined in the cfg config file. Is updated everytime function config_update() is called.

Definition at line 128 of file no_collision_alg.h.

Definition at line 90 of file no_collision_alg.h.

Definition at line 80 of file no_collision_alg.h.

Definition at line 94 of file no_collision_alg.h.

Definition at line 84 of file no_collision_alg.h.

Definition at line 74 of file no_collision_alg.h.

Definition at line 88 of file no_collision_alg.h.

Definition at line 78 of file no_collision_alg.h.

Definition at line 86 of file no_collision_alg.h.

Definition at line 76 of file no_collision_alg.h.

Definition at line 67 of file no_collision_alg.h.

float NoCollisionAlgorithm::heading [protected]

Definition at line 92 of file no_collision_alg.h.

Definition at line 59 of file no_collision_alg.h.

Definition at line 71 of file no_collision_alg.h.

const float NoCollisionAlgorithm::MIN_LASER_RANGE_ = 0.005f [static, protected]

Definition at line 56 of file no_collision_alg.h.

Definition at line 64 of file no_collision_alg.h.

Definition at line 58 of file no_collision_alg.h.

Definition at line 69 of file no_collision_alg.h.

float NoCollisionAlgorithm::R_ACC_ [protected]

Definition at line 66 of file no_collision_alg.h.

float NoCollisionAlgorithm::T_ACC_ [protected]

Definition at line 61 of file no_collision_alg.h.

Definition at line 89 of file no_collision_alg.h.

Definition at line 79 of file no_collision_alg.h.

Definition at line 85 of file no_collision_alg.h.

Definition at line 75 of file no_collision_alg.h.

float NoCollisionAlgorithm::VR_MAX_ [protected]

Definition at line 65 of file no_collision_alg.h.

Definition at line 91 of file no_collision_alg.h.

float NoCollisionAlgorithm::VT_MAX_ [protected]

Definition at line 60 of file no_collision_alg.h.

Definition at line 81 of file no_collision_alg.h.


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


iri_no_collision
Author(s):
autogenerated on Fri Dec 6 2013 21:10:48