#include <jockey.h>
Public Member Functions | |
void | handleCostmap (const nav_msgs::OccupancyGridConstPtr &msg) |
Jockey (const std::string &name, const double frontier_width) | |
virtual void | onContinue () |
virtual void | onInterrupt () |
virtual void | onStop () |
virtual void | onTraverse () |
Private Member Functions | |
void | initTwistHandlerParam () |
Private Attributes | |
lama_msgs::Crossing | abs_crossing_ |
Crossing descriptor with relative position and absolute angle. | |
ros::Subscriber | costmap_handler_ |
crossing_detector::CostmapCrossingDetector | crossing_detector_ |
Compute the crossing. | |
goto_crossing::CrossingGoer | crossing_goer_ |
Compute the twist to go to crossing center. | |
bool | has_crossing_ |
true when a new crossing was computed. | |
double | last_map_orientation_ |
Map orientation of last received map. | |
nav_msgs::OccupancyGrid | map_ |
Last received map. | |
nj_oa_costmap::TwistHandler | obstacle_avoider_ |
Compute the twist for obstacle avoidance. | |
std::string | odom_frame_ |
ros::Publisher | pub_crossing_ |
ros::Publisher | pub_crossing_marker_ |
ros::Publisher | pub_exits_marker_ |
ros::Publisher | pub_place_profile_ |
ros::Publisher | pub_twist_ |
double | range_cutoff_ |
A range longer that this is considered to be free (m). | |
bool | range_cutoff_set_ |
lama_msgs::Crossing | rel_crossing_ |
Crossing descriptor with relative position and relative angle. | |
tf::TransformListener | tf_listener_ |
nj_costmap::Jockey::Jockey | ( | const std::string & | name, |
const double | frontier_width | ||
) |
Definition at line 6 of file jockey.cpp.
void nj_costmap::Jockey::handleCostmap | ( | const nav_msgs::OccupancyGridConstPtr & | msg | ) |
Callback for OccupancyGrid messages.
Definition at line 155 of file jockey.cpp.
void nj_costmap::Jockey::initTwistHandlerParam | ( | ) | [private] |
Definition at line 27 of file jockey.cpp.
void nj_costmap::Jockey::onContinue | ( | ) | [virtual] |
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 147 of file jockey.cpp.
void nj_costmap::Jockey::onInterrupt | ( | ) | [virtual] |
Reimplemented from lama_jockeys::NavigatingJockey.
Definition at line 141 of file jockey.cpp.
void nj_costmap::Jockey::onStop | ( | ) | [virtual] |
Implements lama_jockeys::NavigatingJockey.
Definition at line 132 of file jockey.cpp.
void nj_costmap::Jockey::onTraverse | ( | ) | [virtual] |
Implements lama_jockeys::NavigatingJockey.
Definition at line 58 of file jockey.cpp.
lama_msgs::Crossing nj_costmap::Jockey::abs_crossing_ [private] |
bool nj_costmap::Jockey::has_crossing_ [private] |
double nj_costmap::Jockey::last_map_orientation_ [private] |
nav_msgs::OccupancyGrid nj_costmap::Jockey::map_ [private] |
std::string nj_costmap::Jockey::odom_frame_ [private] |
ros::Publisher nj_costmap::Jockey::pub_twist_ [private] |
double nj_costmap::Jockey::range_cutoff_ [private] |
bool nj_costmap::Jockey::range_cutoff_set_ [private] |
lama_msgs::Crossing nj_costmap::Jockey::rel_crossing_ [private] |