IRI ROS Specific Driver Class. More...
#include <no_collision_alg.h>
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 ¤t_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 |
IRI ROS Specific Driver Class.
Definition at line 44 of file no_collision_alg.h.
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
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.
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.
new_cfg | the new driver configuration state |
level | level 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.
p | input cartesian point |
module | output polar module |
agnle | output 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.
void NoCollisionAlgorithm::getDistance2Goal | ( | geometry_msgs::Pose & | current_goal | ) |
Definition at line 185 of file no_collision_alg.cpp.
bool NoCollisionAlgorithm::isGoalReached | ( | void | ) |
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.
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).
laser | current laser scan |
safety_distance | platfom's safety/clear distance |
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.
scan | current laser scan |
local_goal | requested pose goal in local coordinates |
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.
void NoCollisionAlgorithm::setTranslationalSpeed | ( | const double | vt | ) |
Definition at line 145 of file no_collision_alg.cpp.
bool NoCollisionAlgorithm::try_enter | ( | void | ) | [inline] |
Tries Access to Algorithm.
Tries access to Algorithm
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.
void NoCollisionAlgorithm::updateRotationTrajParams | ( | void | ) | [protected] |
Definition at line 76 of file no_collision_alg.cpp.
void NoCollisionAlgorithm::updateTranslationTrajParams | ( | void | ) | [protected] |
Definition at line 61 of file no_collision_alg.cpp.
float NoCollisionAlgorithm::acc_angle_ [protected] |
Definition at line 87 of file no_collision_alg.h.
float NoCollisionAlgorithm::acc_dist_ [protected] |
Definition at line 77 of file no_collision_alg.h.
CMutex NoCollisionAlgorithm::alg_mutex_ [protected] |
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.
float NoCollisionAlgorithm::ANGLE_TOL_ [protected] |
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.
float NoCollisionAlgorithm::current_angle_ [protected] |
Definition at line 90 of file no_collision_alg.h.
float NoCollisionAlgorithm::current_dist_ [protected] |
Definition at line 80 of file no_collision_alg.h.
ros::Time NoCollisionAlgorithm::current_time_ [protected] |
Definition at line 94 of file no_collision_alg.h.
float NoCollisionAlgorithm::current_vr_ [protected] |
Definition at line 84 of file no_collision_alg.h.
float NoCollisionAlgorithm::current_vt_ [protected] |
Definition at line 74 of file no_collision_alg.h.
float NoCollisionAlgorithm::deacc_angle_ [protected] |
Definition at line 88 of file no_collision_alg.h.
float NoCollisionAlgorithm::deacc_dist_ [protected] |
Definition at line 78 of file no_collision_alg.h.
float NoCollisionAlgorithm::desired_vr_ [protected] |
Definition at line 86 of file no_collision_alg.h.
float NoCollisionAlgorithm::desired_vt_ [protected] |
Definition at line 76 of file no_collision_alg.h.
float NoCollisionAlgorithm::DIST_TOL_ [protected] |
Definition at line 67 of file no_collision_alg.h.
float NoCollisionAlgorithm::heading [protected] |
Definition at line 92 of file no_collision_alg.h.
float NoCollisionAlgorithm::LASER_SAFE_DIST_ [protected] |
Definition at line 59 of file no_collision_alg.h.
float NoCollisionAlgorithm::MAX_ANGLE_TO_STOP_ [protected] |
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.
float NoCollisionAlgorithm::MIN_SAFE_ANGLE_ [protected] |
Definition at line 64 of file no_collision_alg.h.
float NoCollisionAlgorithm::MIN_SAFE_DISTANCE_ [protected] |
Definition at line 58 of file no_collision_alg.h.
float NoCollisionAlgorithm::OA_CONE_ANGLE_ [protected] |
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.
float NoCollisionAlgorithm::target_angle_ [protected] |
Definition at line 89 of file no_collision_alg.h.
float NoCollisionAlgorithm::target_dist_ [protected] |
Definition at line 79 of file no_collision_alg.h.
float NoCollisionAlgorithm::target_vr_ [protected] |
Definition at line 85 of file no_collision_alg.h.
float NoCollisionAlgorithm::target_vt_ [protected] |
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.
TrajStates NoCollisionAlgorithm::vr_state_ [protected] |
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.
TrajStates NoCollisionAlgorithm::vt_state_ [protected] |
Definition at line 81 of file no_collision_alg.h.