Public Member Functions | Protected Attributes | List of all members
planner_cspace::planner_3d::JumpDetector Class Reference

#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::Buffertfbuf_
 
double yaw_jump_
 

Detailed Description

Definition at line 46 of file jump_detector.h.

Constructor & Destructor Documentation

planner_cspace::planner_3d::JumpDetector::JumpDetector ( tf2_ros::Buffer tfbuf)
inlineexplicit

Definition at line 62 of file jump_detector.h.

Member Function Documentation

bool planner_cspace::planner_3d::JumpDetector::detectJump ( )
inline

Definition at line 82 of file jump_detector.h.

void planner_cspace::planner_3d::JumpDetector::setBaseFrame ( const std::string &  frame_id)
inline

Definition at line 73 of file jump_detector.h.

void planner_cspace::planner_3d::JumpDetector::setMapFrame ( const std::string &  frame_id)
inline

Definition at line 69 of file jump_detector.h.

void planner_cspace::planner_3d::JumpDetector::setThresholds ( const double  pos_jump,
const double  yaw_jump 
)
inline

Definition at line 77 of file jump_detector.h.

Member Data Documentation

tf2::Transform planner_cspace::planner_3d::JumpDetector::base_trans_prev_
protected

Definition at line 50 of file jump_detector.h.

bool planner_cspace::planner_3d::JumpDetector::init_
protected

Definition at line 59 of file jump_detector.h.

std::string planner_cspace::planner_3d::JumpDetector::jump_detect_frame_
protected

Definition at line 53 of file jump_detector.h.

std::string planner_cspace::planner_3d::JumpDetector::map_frame_
protected

Definition at line 54 of file jump_detector.h.

tf2::Transform planner_cspace::planner_3d::JumpDetector::map_trans_prev_
protected

Definition at line 51 of file jump_detector.h.

double planner_cspace::planner_3d::JumpDetector::pos_jump_
protected

Definition at line 56 of file jump_detector.h.

tf2_ros::Buffer& planner_cspace::planner_3d::JumpDetector::tfbuf_
protected

Definition at line 49 of file jump_detector.h.

double planner_cspace::planner_3d::JumpDetector::yaw_jump_
protected

Definition at line 57 of file jump_detector.h.


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


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:43