#include <eband_trajectory_controller.h>
◆ EBandTrajectoryCtrl() [1/2]
      
        
          | eband_local_planner::EBandTrajectoryCtrl::EBandTrajectoryCtrl | ( |  | ) |  | 
      
 
 
◆ EBandTrajectoryCtrl() [2/2]
      
        
          | eband_local_planner::EBandTrajectoryCtrl::EBandTrajectoryCtrl | ( | std::string | name, | 
        
          |  |  | costmap_2d::Costmap2DROS * | costmap_ros | 
        
          |  | ) |  |  | 
      
 
Constructs the elastic band object. 
- Parameters
- 
  
    | name | The name to give this instance of the elastic band local planner |  | costmap | The cost map to use for assigning costs to trajectories |  
 
Definition at line 50 of file eband_trajectory_controller.cpp.
 
 
◆ ~EBandTrajectoryCtrl()
      
        
          | eband_local_planner::EBandTrajectoryCtrl::~EBandTrajectoryCtrl | ( |  | ) |  | 
      
 
 
◆ getBubbleTargetVel()
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::getBubbleTargetVel | ( | const int & | target_bub_num, |  
          |  |  | const std::vector< Bubble > & | band, |  
          |  |  | geometry_msgs::Twist & | VelDir |  
          |  | ) |  |  |  | private | 
 
gets the max velocity allowed within this bubble depending on size of the bubble and pose and size of the following bubble 
- Parameters
- 
  
    | number | of the bubble of interest within the band |  | band | in which the bubble is in |  
 
- Returns
- absolute value of maximum allowed velocity within this bubble 
Definition at line 706 of file eband_trajectory_controller.cpp.
 
 
◆ getFrame1ToFrame2InRefFrame()
Transforms Pose of frame 1 and 2 into reference frame and gets difference of frame 1 and 2. 
- Parameters
- 
  
    | refernce | to pose of frame1 |  | reference | to pose of frame2 |  | reference | to pose of reference frame |  
 
- Returns
- vector from frame1 to frame2 in coordinates of the reference frame 
Definition at line 766 of file eband_trajectory_controller.cpp.
 
 
◆ getFrame1ToFrame2InRefFrameNew()
◆ getTwist()
      
        
          | bool eband_local_planner::EBandTrajectoryCtrl::getTwist | ( | geometry_msgs::Twist & | twist_cmd, | 
        
          |  |  | bool & | goal_reached | 
        
          |  | ) |  |  | 
      
 
 
◆ getTwistDifferentialDrive()
      
        
          | bool eband_local_planner::EBandTrajectoryCtrl::getTwistDifferentialDrive | ( | geometry_msgs::Twist & | twist_cmd, | 
        
          |  |  | bool & | goal_reached | 
        
          |  | ) |  |  | 
      
 
 
◆ initialize()
Initializes the elastic band class by accesing costmap and loading parameters. 
- Parameters
- 
  
    | name | The name to give this instance of the trajectory planner |  | costmap | The cost map to use for assigning costs to trajectories |  
 
Definition at line 64 of file eband_trajectory_controller.cpp.
 
 
◆ limitTwist()
  
  | 
        
          | geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::limitTwist | ( | const geometry_msgs::Twist & | twist | ) |  |  | private | 
 
limits the twist to the allowed range 
- Parameters
- 
  
    | reference | to unconstrained twist |  
 
- Returns
- twist in allowed range 
Definition at line 858 of file eband_trajectory_controller.cpp.
 
 
◆ reconfigure()
      
        
          | void eband_local_planner::EBandTrajectoryCtrl::reconfigure | ( | EBandPlannerConfig & | config | ) |  | 
      
 
 
◆ setBand()
      
        
          | bool eband_local_planner::EBandTrajectoryCtrl::setBand | ( | const std::vector< Bubble > & | elastic_band | ) |  | 
      
 
 
◆ setOdometry()
      
        
          | bool eband_local_planner::EBandTrajectoryCtrl::setOdometry | ( | const nav_msgs::Odometry & | odometry | ) |  | 
      
 
 
◆ setVisualization()
passes a reference to the eband visualization object which can be used to visualize the band optimization 
- Parameters
- 
  
    | pointer | to visualization object |  
 
Definition at line 131 of file eband_trajectory_controller.cpp.
 
 
◆ sign()
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::sign | ( | double | n | ) |  |  | inlineprivate | 
 
 
◆ transformTwistFromFrame1ToFrame2()
  
  | 
        
          | geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::transformTwistFromFrame1ToFrame2 | ( | const geometry_msgs::Twist & | curr_twist, |  
          |  |  | const geometry_msgs::Pose & | frame1, |  
          |  |  | const geometry_msgs::Pose & | frame2 |  
          |  | ) |  |  |  | private | 
 
- Parameters
- 
  
    | Transforms | twist into a given reference frame |  | Twist | that shall be transformed |  | refernce | to pose of frame1 |  | reference | to pose of frame2 |  
 
- Returns
- transformed twist 
Definition at line 833 of file eband_trajectory_controller.cpp.
 
 
◆ acc_max_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::acc_max_ |  | private | 
 
 
◆ acc_max_rot_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::acc_max_rot_ |  | private | 
 
 
◆ acc_max_trans_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::acc_max_trans_ |  | private | 
 
 
◆ band_set_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::band_set_ |  | private | 
 
 
◆ bubble_velocity_multiplier_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::bubble_velocity_multiplier_ |  | private | 
 
 
◆ costmap_ros_
◆ ctrl_freq_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::ctrl_freq_ |  | private | 
 
 
◆ differential_drive_hack_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::differential_drive_hack_ |  | private | 
 
 
◆ disallow_hysteresis_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::disallow_hysteresis_ |  | private | 
 
 
◆ elastic_band_
  
  | 
        
          | std::vector<Bubble> eband_local_planner::EBandTrajectoryCtrl::elastic_band_ |  | private | 
 
 
◆ in_final_goal_turn_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::in_final_goal_turn_ |  | private | 
 
 
◆ in_place_trans_vel_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::in_place_trans_vel_ |  | private | 
 
 
◆ initialized_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::initialized_ |  | private | 
 
 
◆ k_nu_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::k_nu_ |  | private | 
 
 
◆ k_p_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::k_p_ |  | private | 
 
 
◆ last_vel_
  
  | 
        
          | geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::last_vel_ |  | private | 
 
 
◆ max_vel_lin_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::max_vel_lin_ |  | private | 
 
 
◆ max_vel_th_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::max_vel_th_ |  | private | 
 
 
◆ min_in_place_vel_th_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::min_in_place_vel_th_ |  | private | 
 
 
◆ min_vel_lin_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::min_vel_lin_ |  | private | 
 
 
◆ min_vel_th_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::min_vel_th_ |  | private | 
 
 
◆ odom_vel_
  
  | 
        
          | geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::odom_vel_ |  | private | 
 
 
◆ pid_
◆ ref_frame_band_
◆ rotation_correction_threshold_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::rotation_correction_threshold_ |  | private | 
 
 
◆ rotation_threshold_multiplier_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::rotation_threshold_multiplier_ |  | private | 
 
 
◆ target_visual_
◆ tolerance_rot_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::tolerance_rot_ |  | private | 
 
 
◆ tolerance_trans_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::tolerance_trans_ |  | private | 
 
 
◆ virt_mass_
  
  | 
        
          | double eband_local_planner::EBandTrajectoryCtrl::virt_mass_ |  | private | 
 
 
◆ visualization_
  
  | 
        
          | bool eband_local_planner::EBandTrajectoryCtrl::visualization_ |  | private | 
 
 
The documentation for this class was generated from the following files: