Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
lj_laser_heading::Jockey Class Reference

#include <jockey.h>

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

List of all members.

Public Member Functions

 Jockey (std::string name, const double frontier_width, const double max_frontier_angle=0.785)

Private Member Functions

void getData ()
void handleLaser (const sensor_msgs::LaserScanConstPtr &msg)
void handleOdom (const nav_msgs::OdometryConstPtr &msg)
void handlePose (const geometry_msgs::PoseConstPtr &msg)
void initMapCrossingInterface ()
void initMapLaserInterface ()
void rotateScan ()

Private Attributes

double heading_
 Heading information read from Pose or Odometry.
ros::Time heading_reception_time_
ros::Subscriber odomHandler_
ros::Subscriber poseHandler_

Static Private Attributes

static const ros::Duration max_data_time_delta_ = ros::Duration(0.050)
 Max time interval between reception of scan_ and heading_.

Detailed Description

Definition at line 42 of file jockey.h.


Constructor & Destructor Documentation

lj_laser_heading::Jockey::Jockey ( std::string  name,
const double  frontier_width,
const double  max_frontier_angle = 0.785 
)

Reimplemented from lj_laser::Jockey.

Definition at line 13 of file jockey.cpp.


Member Function Documentation

Reimplemented from lj_laser::Jockey.

Definition at line 21 of file jockey.cpp.

void lj_laser_heading::Jockey::handleLaser ( const sensor_msgs::LaserScanConstPtr &  msg) [private]

Reimplemented from lj_laser::Jockey.

Definition at line 58 of file jockey.cpp.

void lj_laser_heading::Jockey::handleOdom ( const nav_msgs::OdometryConstPtr &  msg) [private]

Definition at line 98 of file jockey.cpp.

void lj_laser_heading::Jockey::handlePose ( const geometry_msgs::PoseConstPtr &  msg) [private]

Definition at line 87 of file jockey.cpp.

Reimplemented from lj_laser::Jockey.

Reimplemented from lj_laser::Jockey.

Definition at line 50 of file jockey.cpp.


Member Data Documentation

Heading information read from Pose or Odometry.

Definition at line 63 of file jockey.h.

Definition at line 62 of file jockey.h.

Max time interval between reception of scan_ and heading_.

Definition at line 66 of file jockey.h.

Definition at line 61 of file jockey.h.

Definition at line 60 of file jockey.h.


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


lj_laser_heading
Author(s): Gaƫl Ecorchard
autogenerated on Thu Jun 6 2019 17:50:49