#include <crossing_escaper.h>
Public Member Functions | |
CrossingEscaper (std::string name, double escape_distance=0) | |
Protected Member Functions | |
void | direction_callback (const std_msgs::Float32 &direction) |
void | odometry_callback (const nav_msgs::Odometry &odometry) |
virtual void | onStop () |
virtual void | onTraverse () |
Private Member Functions | |
bool | getCrossing () |
bool | getDistanceToEscape () |
bool | getExitAngleFromMap () |
void | getExitDirection () |
geometry_msgs::Point | goalFromOdometry (double dx, double dy) |
bool | goToGoal (const geometry_msgs::Point &goal, geometry_msgs::Twist &twist) |
bool | retrieveCrossingFromMap (int32_t descriptor_id) |
bool | turnToAngle (double direction, geometry_msgs::Twist &twist) |
Private Attributes | |
bool | angle_reached_ |
lama_msgs::Crossing | crossing_ |
ros::ServiceClient | crossing_getter_ |
std::string | crossing_interface_name_ |
Name of the map interface for crossing. | |
double | direction_ |
double | distance_reached_ |
double | distance_to_escape_ |
Either escape_distance_ or crossing_.radius. | |
double | escape_distance_ |
Distance to travel from crossing center (m). | |
ros::ServiceClient | exit_angle_getter_ |
std::string | exit_angle_interface_name_ |
Name of the map interface for exit angle. | |
std::string | exit_angle_topic_name_ |
Name of the optional topic for exit angle (or direction). | |
bool | goal_reached_ |
bool | has_direction_ |
bool | has_odometry_ |
double | kp_v_ |
Proportional gain for the linear velocity (s^-1). | |
double | kp_w_ |
Proportional gain for the angular velocity (s^-1). | |
double | last_dtheta_ |
Last measured dtheta, used for zero-crossing detection. | |
double | max_angle_turn_only_ |
If dtheta is greater than this, only turn, do not go forward (rad). | |
double | max_angular_velocity_ |
double | max_linear_velocity_ |
double | max_odometry_age_ |
If Odometry is not received withing this time, set null Twist (s). | |
double | min_angular_velocity_ |
Minimum angular set velocity (rad.s^-1). | |
double | min_linear_velocity_ |
Minimum linear set velocity (m.s^-1) | |
nav_msgs::Odometry | odometry_ |
ros::Subscriber | odometry_subscriber_ |
nav_msgs::Odometry | start_position_ |
bool | start_reached_ |
ros::Publisher | twist_publisher_ |
Definition at line 72 of file crossing_escaper.h.
nj_escape_crossing::CrossingEscaper::CrossingEscaper | ( | std::string | name, |
double | escape_distance = 0 |
||
) |
Definition at line 6 of file crossing_escaper.cpp.
void nj_escape_crossing::CrossingEscaper::direction_callback | ( | const std_msgs::Float32 & | direction | ) | [protected] |
Definition at line 178 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::getCrossing | ( | ) | [private] |
Definition at line 227 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::getDistanceToEscape | ( | ) | [private] |
Get the distance to escape (sets distance_to_escape_).
Its value is taken from, in order:
Definition at line 191 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::getExitAngleFromMap | ( | ) | [private] |
Set direction_ to the exit angle descriptor associated with goal_.edge
Definition at line 347 of file crossing_escaper.cpp.
void nj_escape_crossing::CrossingEscaper::getExitDirection | ( | ) | [private] |
Retrieve the direction in which to exit and wait for odometry.
The odometry gives the start position.
In order:
Definition at line 298 of file crossing_escaper.cpp.
geometry_msgs::Point nj_escape_crossing::CrossingEscaper::goalFromOdometry | ( | double | dx, |
double | dy | ||
) | [private] |
Return the relative goal from current robot position and start position
[in] | dx | relative goal, at start. |
[in] | dy | relative goal, at start. |
Definition at line 505 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::goToGoal | ( | const geometry_msgs::Point & | goal, |
geometry_msgs::Twist & | twist | ||
) | [private] |
GoToGoal behavior
[in] | goal | relative goal. |
[out] | twist | set velocity. |
Definition at line 422 of file crossing_escaper.cpp.
void nj_escape_crossing::CrossingEscaper::odometry_callback | ( | const nav_msgs::Odometry & | odometry | ) | [protected] |
Definition at line 172 of file crossing_escaper.cpp.
void nj_escape_crossing::CrossingEscaper::onStop | ( | ) | [protected, virtual] |
Implements lama_jockeys::NavigatingJockey.
Definition at line 159 of file crossing_escaper.cpp.
void nj_escape_crossing::CrossingEscaper::onTraverse | ( | ) | [protected, virtual] |
Go to start vertex, orient, go far.
First go to the start vertex of the edge to traverse, then orient the robot, then travel at least "distance_to_escape_".
Implements lama_jockeys::NavigatingJockey.
Definition at line 52 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::retrieveCrossingFromMap | ( | int32_t | descriptor_id | ) | [private] |
Definition at line 274 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::turnToAngle | ( | double | direction, |
geometry_msgs::Twist & | twist | ||
) | [private] |
GoToGoal behavior for pure rotation
[in] | direction | direction the robot should have at the end (in odometry_ frame). |
[out] | twist | set velocity. |
Definition at line 390 of file crossing_escaper.cpp.
bool nj_escape_crossing::CrossingEscaper::angle_reached_ [private] |
Definition at line 121 of file crossing_escaper.h.
lama_msgs::Crossing nj_escape_crossing::CrossingEscaper::crossing_ [private] |
Definition at line 124 of file crossing_escaper.h.
Definition at line 100 of file crossing_escaper.h.
std::string nj_escape_crossing::CrossingEscaper::crossing_interface_name_ [private] |
Name of the map interface for crossing.
Definition at line 130 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::direction_ [private] |
Definition at line 126 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::distance_reached_ [private] |
Distance when considering reached target when going to the start vertex (m).
Definition at line 113 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::distance_to_escape_ [private] |
Either escape_distance_ or crossing_.radius.
Definition at line 129 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::escape_distance_ [private] |
Distance to travel from crossing center (m).
Definition at line 112 of file crossing_escaper.h.
Definition at line 101 of file crossing_escaper.h.
std::string nj_escape_crossing::CrossingEscaper::exit_angle_interface_name_ [private] |
Name of the map interface for exit angle.
Definition at line 131 of file crossing_escaper.h.
std::string nj_escape_crossing::CrossingEscaper::exit_angle_topic_name_ [private] |
Name of the optional topic for exit angle (or direction).
Definition at line 117 of file crossing_escaper.h.
bool nj_escape_crossing::CrossingEscaper::goal_reached_ [private] |
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 122 of file crossing_escaper.h.
bool nj_escape_crossing::CrossingEscaper::has_direction_ [private] |
Definition at line 127 of file crossing_escaper.h.
bool nj_escape_crossing::CrossingEscaper::has_odometry_ [private] |
Definition at line 123 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::kp_v_ [private] |
Proportional gain for the linear velocity (s^-1).
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 104 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::kp_w_ [private] |
Proportional gain for the angular velocity (s^-1).
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 105 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::last_dtheta_ [private] |
Last measured dtheta, used for zero-crossing detection.
Definition at line 132 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::max_angle_turn_only_ [private] |
If dtheta is greater than this, only turn, do not go forward (rad).
Definition at line 115 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::max_angular_velocity_ [private] |
maximum angular set velocity (rad.s^-1). if set to 0, the angular velocity is not throttled.
Definition at line 110 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::max_linear_velocity_ [private] |
Maximum linear set velocity (m.s^-1). If set to 0, the velocity is not throttled.
Definition at line 107 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::max_odometry_age_ [private] |
If Odometry is not received withing this time, set null Twist (s).
Definition at line 116 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::min_angular_velocity_ [private] |
Minimum angular set velocity (rad.s^-1).
Definition at line 109 of file crossing_escaper.h.
double nj_escape_crossing::CrossingEscaper::min_linear_velocity_ [private] |
Minimum linear set velocity (m.s^-1)
Definition at line 106 of file crossing_escaper.h.
nav_msgs::Odometry nj_escape_crossing::CrossingEscaper::odometry_ [private] |
Definition at line 125 of file crossing_escaper.h.
Definition at line 98 of file crossing_escaper.h.
nav_msgs::Odometry nj_escape_crossing::CrossingEscaper::start_position_ [private] |
Definition at line 128 of file crossing_escaper.h.
bool nj_escape_crossing::CrossingEscaper::start_reached_ [private] |
Definition at line 120 of file crossing_escaper.h.
Definition at line 99 of file crossing_escaper.h.