Public Member Functions | Private Member Functions | Private Attributes | List of all members
eband_local_planner::EBandTrajectoryCtrl Class Reference

#include <eband_trajectory_controller.h>

Public Member Functions

 EBandTrajectoryCtrl ()
 Default constructor. More...
 
 EBandTrajectoryCtrl (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the elastic band object. More...
 
bool getTwist (geometry_msgs::Twist &twist_cmd, bool &goal_reached)
 calculates a twist feedforward command from the current band More...
 
bool getTwistDifferentialDrive (geometry_msgs::Twist &twist_cmd, bool &goal_reached)
 
void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Initializes the elastic band class by accesing costmap and loading parameters. More...
 
void reconfigure (EBandPlannerConfig &config)
 Reconfigures the parameters of the planner. More...
 
bool setBand (const std::vector< Bubble > &elastic_band)
 This sets the elastic_band to the trajectory controller. More...
 
bool setOdometry (const nav_msgs::Odometry &odometry)
 This sets the robot velocity as provided by odometry. More...
 
void setVisualization (boost::shared_ptr< EBandVisualization > target_visual)
 passes a reference to the eband visualization object which can be used to visualize the band optimization More...
 
 ~EBandTrajectoryCtrl ()
 Destructor. More...
 

Private Member Functions

double getBubbleTargetVel (const int &target_bub_num, const std::vector< Bubble > &band, geometry_msgs::Twist &VelDir)
 gets the max velocity allowed within this bubble depending on size of the bubble and pose and size of the following bubble More...
 
geometry_msgs::Twist getFrame1ToFrame2InRefFrame (const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
 Transforms Pose of frame 1 and 2 into reference frame and gets difference of frame 1 and 2. More...
 
geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew (const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
 
geometry_msgs::Twist limitTwist (const geometry_msgs::Twist &twist)
 limits the twist to the allowed range More...
 
double sign (double n)
 defines sign of a double More...
 
geometry_msgs::Twist transformTwistFromFrame1ToFrame2 (const geometry_msgs::Twist &curr_twist, const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2)
 

Private Attributes

double acc_max_
 
double acc_max_rot_
 
double acc_max_trans_
 
bool band_set_
 
double bubble_velocity_multiplier_
 
costmap_2d::Costmap2DROScostmap_ros_
 pointer to costmap More...
 
double ctrl_freq_
 
bool differential_drive_hack_
 
bool disallow_hysteresis_
 
std::vector< Bubbleelastic_band_
 
bool in_final_goal_turn_
 
double in_place_trans_vel_
 
bool initialized_
 
double k_nu_
 
double k_p_
 
geometry_msgs::Twist last_vel_
 
double max_vel_lin_
 
double max_vel_th_
 
double min_in_place_vel_th_
 
double min_vel_lin_
 
double min_vel_th_
 
geometry_msgs::Twist odom_vel_
 
control_toolbox::Pid pid_
 
geometry_msgs::Pose ref_frame_band_
 
double rotation_correction_threshold_
 
double rotation_threshold_multiplier_
 
boost::shared_ptr< EBandVisualizationtarget_visual_
 
double tolerance_rot_
 
double tolerance_trans_
 
double virt_mass_
 
bool visualization_
 

Detailed Description

Definition at line 70 of file eband_trajectory_controller.h.

Constructor & Destructor Documentation

◆ EBandTrajectoryCtrl() [1/2]

eband_local_planner::EBandTrajectoryCtrl::EBandTrajectoryCtrl ( )

Default constructor.

Definition at line 47 of file eband_trajectory_controller.cpp.

◆ EBandTrajectoryCtrl() [2/2]

eband_local_planner::EBandTrajectoryCtrl::EBandTrajectoryCtrl ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Constructs the elastic band object.

Parameters
nameThe name to give this instance of the elastic band local planner
costmapThe 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 ( )

Destructor.

Definition at line 61 of file eband_trajectory_controller.cpp.

Member Function Documentation

◆ 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
numberof the bubble of interest within the band
bandin 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()

geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrame ( const geometry_msgs::Pose frame1,
const geometry_msgs::Pose frame2,
const geometry_msgs::Pose ref_frame 
)
private

Transforms Pose of frame 1 and 2 into reference frame and gets difference of frame 1 and 2.

Parameters
refernceto pose of frame1
referenceto pose of frame2
referenceto 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()

geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrameNew ( const geometry_msgs::Pose frame1,
const geometry_msgs::Pose frame2,
const geometry_msgs::Pose ref_frame 
)
private

Definition at line 806 of file eband_trajectory_controller.cpp.

◆ getTwist()

bool eband_local_planner::EBandTrajectoryCtrl::getTwist ( geometry_msgs::Twist &  twist_cmd,
bool &  goal_reached 
)

calculates a twist feedforward command from the current band

Parameters
refernceto the twist cmd

Definition at line 352 of file eband_trajectory_controller.cpp.

◆ getTwistDifferentialDrive()

bool eband_local_planner::EBandTrajectoryCtrl::getTwistDifferentialDrive ( geometry_msgs::Twist &  twist_cmd,
bool &  goal_reached 
)

Definition at line 176 of file eband_trajectory_controller.cpp.

◆ initialize()

void eband_local_planner::EBandTrajectoryCtrl::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)

Initializes the elastic band class by accesing costmap and loading parameters.

Parameters
nameThe name to give this instance of the trajectory planner
costmapThe 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
referenceto 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)

Reconfigures the parameters of the planner.

Parameters
configThe dynamic reconfigure configuration

Definition at line 103 of file eband_trajectory_controller.cpp.

◆ setBand()

bool eband_local_planner::EBandTrajectoryCtrl::setBand ( const std::vector< Bubble > &  elastic_band)

This sets the elastic_band to the trajectory controller.

Parameters
referencevia which the band is passed

Definition at line 138 of file eband_trajectory_controller.cpp.

◆ setOdometry()

bool eband_local_planner::EBandTrajectoryCtrl::setOdometry ( const nav_msgs::Odometry &  odometry)

This sets the robot velocity as provided by odometry.

Parameters
referencevia which odometry is passed

Definition at line 146 of file eband_trajectory_controller.cpp.

◆ setVisualization()

void eband_local_planner::EBandTrajectoryCtrl::setVisualization ( boost::shared_ptr< EBandVisualization target_visual)

passes a reference to the eband visualization object which can be used to visualize the band optimization

Parameters
pointerto visualization object

Definition at line 131 of file eband_trajectory_controller.cpp.

◆ sign()

double eband_local_planner::EBandTrajectoryCtrl::sign ( double  n)
inlineprivate

defines sign of a double

Definition at line 165 of file eband_trajectory_controller.h.

◆ 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
Transformstwist into a given reference frame
Twistthat shall be transformed
refernceto pose of frame1
referenceto pose of frame2
Returns
transformed twist

Definition at line 833 of file eband_trajectory_controller.cpp.

Member Data Documentation

◆ acc_max_

double eband_local_planner::EBandTrajectoryCtrl::acc_max_
private

Definition at line 141 of file eband_trajectory_controller.h.

◆ acc_max_rot_

double eband_local_planner::EBandTrajectoryCtrl::acc_max_rot_
private

Definition at line 146 of file eband_trajectory_controller.h.

◆ acc_max_trans_

double eband_local_planner::EBandTrajectoryCtrl::acc_max_trans_
private

Definition at line 146 of file eband_trajectory_controller.h.

◆ band_set_

bool eband_local_planner::EBandTrajectoryCtrl::band_set_
private

Definition at line 156 of file eband_trajectory_controller.h.

◆ bubble_velocity_multiplier_

double eband_local_planner::EBandTrajectoryCtrl::bubble_velocity_multiplier_
private

Definition at line 150 of file eband_trajectory_controller.h.

◆ costmap_ros_

costmap_2d::Costmap2DROS* eband_local_planner::EBandTrajectoryCtrl::costmap_ros_
private

pointer to costmap

Definition at line 133 of file eband_trajectory_controller.h.

◆ ctrl_freq_

double eband_local_planner::EBandTrajectoryCtrl::ctrl_freq_
private

Definition at line 140 of file eband_trajectory_controller.h.

◆ differential_drive_hack_

bool eband_local_planner::EBandTrajectoryCtrl::differential_drive_hack_
private

Definition at line 139 of file eband_trajectory_controller.h.

◆ disallow_hysteresis_

bool eband_local_planner::EBandTrajectoryCtrl::disallow_hysteresis_
private

Definition at line 152 of file eband_trajectory_controller.h.

◆ elastic_band_

std::vector<Bubble> eband_local_planner::EBandTrajectoryCtrl::elastic_band_
private

Definition at line 159 of file eband_trajectory_controller.h.

◆ in_final_goal_turn_

bool eband_local_planner::EBandTrajectoryCtrl::in_final_goal_turn_
private

Definition at line 153 of file eband_trajectory_controller.h.

◆ in_place_trans_vel_

double eband_local_planner::EBandTrajectoryCtrl::in_place_trans_vel_
private

Definition at line 144 of file eband_trajectory_controller.h.

◆ initialized_

bool eband_local_planner::EBandTrajectoryCtrl::initialized_
private

Definition at line 156 of file eband_trajectory_controller.h.

◆ k_nu_

double eband_local_planner::EBandTrajectoryCtrl::k_nu_
private

Definition at line 140 of file eband_trajectory_controller.h.

◆ k_p_

double eband_local_planner::EBandTrajectoryCtrl::k_p_
private

Definition at line 140 of file eband_trajectory_controller.h.

◆ last_vel_

geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::last_vel_
private

Definition at line 161 of file eband_trajectory_controller.h.

◆ max_vel_lin_

double eband_local_planner::EBandTrajectoryCtrl::max_vel_lin_
private

Definition at line 142 of file eband_trajectory_controller.h.

◆ max_vel_th_

double eband_local_planner::EBandTrajectoryCtrl::max_vel_th_
private

Definition at line 142 of file eband_trajectory_controller.h.

◆ min_in_place_vel_th_

double eband_local_planner::EBandTrajectoryCtrl::min_in_place_vel_th_
private

Definition at line 143 of file eband_trajectory_controller.h.

◆ min_vel_lin_

double eband_local_planner::EBandTrajectoryCtrl::min_vel_lin_
private

Definition at line 142 of file eband_trajectory_controller.h.

◆ min_vel_th_

double eband_local_planner::EBandTrajectoryCtrl::min_vel_th_
private

Definition at line 142 of file eband_trajectory_controller.h.

◆ odom_vel_

geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::odom_vel_
private

Definition at line 160 of file eband_trajectory_controller.h.

◆ pid_

control_toolbox::Pid eband_local_planner::EBandTrajectoryCtrl::pid_
private

Definition at line 136 of file eband_trajectory_controller.h.

◆ ref_frame_band_

geometry_msgs::Pose eband_local_planner::EBandTrajectoryCtrl::ref_frame_band_
private

Definition at line 162 of file eband_trajectory_controller.h.

◆ rotation_correction_threshold_

double eband_local_planner::EBandTrajectoryCtrl::rotation_correction_threshold_
private

Definition at line 147 of file eband_trajectory_controller.h.

◆ rotation_threshold_multiplier_

double eband_local_planner::EBandTrajectoryCtrl::rotation_threshold_multiplier_
private

Definition at line 151 of file eband_trajectory_controller.h.

◆ target_visual_

boost::shared_ptr<EBandVisualization> eband_local_planner::EBandTrajectoryCtrl::target_visual_
private

Definition at line 134 of file eband_trajectory_controller.h.

◆ tolerance_rot_

double eband_local_planner::EBandTrajectoryCtrl::tolerance_rot_
private

Definition at line 145 of file eband_trajectory_controller.h.

◆ tolerance_trans_

double eband_local_planner::EBandTrajectoryCtrl::tolerance_trans_
private

Definition at line 145 of file eband_trajectory_controller.h.

◆ virt_mass_

double eband_local_planner::EBandTrajectoryCtrl::virt_mass_
private

Definition at line 141 of file eband_trajectory_controller.h.

◆ visualization_

bool eband_local_planner::EBandTrajectoryCtrl::visualization_
private

Definition at line 156 of file eband_trajectory_controller.h.


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


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Mon Feb 28 2022 22:16:50