Public Member Functions | Private Attributes
nj_laser::Jockey Class Reference

#include <jockey.h>

Inheritance diagram for nj_laser::Jockey:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void handleLaser (const sensor_msgs::LaserScanConstPtr &msg)
 Jockey (const std::string &name, const double frontier_width)
virtual void onContinue ()
virtual void onInterrupt ()
virtual void onStop ()
virtual void onTraverse ()

Private Attributes

lama_msgs::Crossing crossing_
 Crossing descriptor from LaserScan.
crossing_detector::LaserCrossingDetector crossing_detector_
goto_crossing::CrossingGoer crossing_goer_
bool has_crossing_
ros::Subscriber laserHandler_
nj_oa_laser::TwistHandler obstacle_avoider_
 Twist computation for obstacle avoidance.
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_
sensor_msgs::LaserScan scan_
 Last received laser scan.

Detailed Description

Definition at line 48 of file jockey.h.


Constructor & Destructor Documentation

nj_laser::Jockey::Jockey ( const std::string &  name,
const double  frontier_width 
)

Definition at line 6 of file jockey.cpp.


Member Function Documentation

void nj_laser::Jockey::handleLaser ( const sensor_msgs::LaserScanConstPtr &  msg)

Definition at line 96 of file jockey.cpp.

void nj_laser::Jockey::onContinue ( ) [virtual]

Reimplemented from lama_jockeys::NavigatingJockey.

Definition at line 90 of file jockey.cpp.

void nj_laser::Jockey::onInterrupt ( ) [virtual]

Reimplemented from lama_jockeys::NavigatingJockey.

Definition at line 84 of file jockey.cpp.

void nj_laser::Jockey::onStop ( ) [virtual]

Implements lama_jockeys::NavigatingJockey.

Definition at line 75 of file jockey.cpp.

void nj_laser::Jockey::onTraverse ( ) [virtual]

Implements lama_jockeys::NavigatingJockey.

Definition at line 26 of file jockey.cpp.


Member Data Documentation

lama_msgs::Crossing nj_laser::Jockey::crossing_ [private]

Crossing descriptor from LaserScan.

Definition at line 77 of file jockey.h.

Definition at line 78 of file jockey.h.

Definition at line 79 of file jockey.h.

Definition at line 75 of file jockey.h.

Definition at line 64 of file jockey.h.

Twist computation for obstacle avoidance.

Definition at line 80 of file jockey.h.

Definition at line 69 of file jockey.h.

Definition at line 65 of file jockey.h.

Definition at line 66 of file jockey.h.

Definition at line 68 of file jockey.h.

Definition at line 67 of file jockey.h.

Definition at line 72 of file jockey.h.

sensor_msgs::LaserScan nj_laser::Jockey::scan_ [private]

Last received laser scan.

Definition at line 76 of file jockey.h.


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


nj_laser
Author(s): Gaël Ecorchard , Karel Košnar , Vojtěch Vonásek
autogenerated on Thu Jun 6 2019 17:50:54