#include <jump_detector.h>
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::Buffer & | tfbuf_ |
tf2_ros::TransformListener | tfl_ |
double | yaw_jump_ |
Definition at line 41 of file jump_detector.h.
|
inlineexplicit |
Definition at line 58 of file jump_detector.h.
|
inline |
Definition at line 79 of file jump_detector.h.
|
inline |
Definition at line 70 of file jump_detector.h.
|
inline |
Definition at line 66 of file jump_detector.h.
|
inline |
Definition at line 74 of file jump_detector.h.
|
protected |
Definition at line 46 of file jump_detector.h.
|
protected |
Definition at line 55 of file jump_detector.h.
|
protected |
Definition at line 49 of file jump_detector.h.
|
protected |
Definition at line 50 of file jump_detector.h.
|
protected |
Definition at line 47 of file jump_detector.h.
|
protected |
Definition at line 52 of file jump_detector.h.
|
protected |
Definition at line 44 of file jump_detector.h.
|
protected |
Definition at line 45 of file jump_detector.h.
|
protected |
Definition at line 53 of file jump_detector.h.