Public Member Functions | Protected Attributes
JumpDetector Class Reference

#include <jump_detector.h>

List of all members.

Public Member Functions

bool detectJump ()
 JumpDetector (tf2_ros::Buffer &tfbuf)
void setBaseFrame (const std::string &frame_id)
void setMapFrame (const std::string &frame_id)
void setThresholds (const double pos_jump, const double yaw_jump)

Protected Attributes

tf2::Transform base_trans_prev_
bool init_
std::string jump_detect_frame_
std::string map_frame_
tf2::Transform map_trans_prev_
double pos_jump_
tf2_ros::Buffertfbuf_
tf2_ros::TransformListener tfl_
double yaw_jump_

Detailed Description

Definition at line 41 of file jump_detector.h.


Constructor & Destructor Documentation

JumpDetector::JumpDetector ( tf2_ros::Buffer tfbuf) [inline, explicit]

Definition at line 58 of file jump_detector.h.


Member Function Documentation

bool JumpDetector::detectJump ( ) [inline]

Definition at line 79 of file jump_detector.h.

void JumpDetector::setBaseFrame ( const std::string &  frame_id) [inline]

Definition at line 70 of file jump_detector.h.

void JumpDetector::setMapFrame ( const std::string &  frame_id) [inline]

Definition at line 66 of file jump_detector.h.

void JumpDetector::setThresholds ( const double  pos_jump,
const double  yaw_jump 
) [inline]

Definition at line 74 of file jump_detector.h.


Member Data Documentation

Definition at line 46 of file jump_detector.h.

bool JumpDetector::init_ [protected]

Definition at line 55 of file jump_detector.h.

std::string JumpDetector::jump_detect_frame_ [protected]

Definition at line 49 of file jump_detector.h.

std::string JumpDetector::map_frame_ [protected]

Definition at line 50 of file jump_detector.h.

Definition at line 47 of file jump_detector.h.

double JumpDetector::pos_jump_ [protected]

Definition at line 52 of file jump_detector.h.

Definition at line 44 of file jump_detector.h.

Definition at line 45 of file jump_detector.h.

double JumpDetector::yaw_jump_ [protected]

Definition at line 53 of file jump_detector.h.


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


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:27