#include <eband_trajectory_controller.h>
Public Member Functions | |
| EBandTrajectoryCtrl () | |
| Default constructor.   | |
| EBandTrajectoryCtrl (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | |
| Constructs the elastic band object.   | |
| bool | getTwist (geometry_msgs::Twist &twist_cmd) | 
| calculates a twist feedforward command from the current band   | |
| void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | 
| Initializes the elastic band class by accesing costmap and loading parameters.   | |
| bool | setBand (const std::vector< Bubble > &elastic_band) | 
| This sets the elastic_band to the trajectory controller.   | |
| bool | setOdometry (const nav_msgs::Odometry &odometry) | 
| This sets the robot velocity as provided by odometry.   | |
| 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   | |
| ~EBandTrajectoryCtrl () | |
| Destructor.   | |
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   | |
| 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.   | |
| geometry_msgs::Twist | limitTwist (const geometry_msgs::Twist &twist) | 
| limits the twist to the allowed range   | |
| double | sign (double n) | 
| defines sign of a double   | |
| 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_ | 
| costmap_2d::Costmap2DROS * | costmap_ros_ | 
| pointer to costmap   | |
| double | ctrl_freq_ | 
| std::vector< Bubble > | elastic_band_ | 
| 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_ | 
| boost::shared_ptr < EBandVisualization >  | target_visual_ | 
| double | tolerance_rot_ | 
| double | tolerance_timeout_ | 
| double | tolerance_trans_ | 
| double | virt_mass_ | 
| bool | visualization_ | 
Definition at line 72 of file eband_trajectory_controller.h.
Default constructor.
Definition at line 48 of file eband_trajectory_controller.cpp.
| eband_local_planner::EBandTrajectoryCtrl::EBandTrajectoryCtrl | ( | std::string | name, | 
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) | 
Constructs the elastic band object.
| 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 51 of file eband_trajectory_controller.cpp.
Destructor.
Definition at line 62 of file eband_trajectory_controller.cpp.
| 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
| number | of the bubble of interest within the band | 
| band | in which the bubble is in | 
Definition at line 522 of file eband_trajectory_controller.cpp.
| 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.
| refernce | to pose of frame1 | 
| reference | to pose of frame2 | 
| reference | to pose of reference frame | 
Definition at line 582 of file eband_trajectory_controller.cpp.
| bool eband_local_planner::EBandTrajectoryCtrl::getTwist | ( | geometry_msgs::Twist & | twist_cmd | ) | 
calculates a twist feedforward command from the current band
| refernce | to the twist cmd | 
Definition at line 174 of file eband_trajectory_controller.cpp.
| 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.
| 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 65 of file eband_trajectory_controller.cpp.
| geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::limitTwist | ( | const geometry_msgs::Twist & | twist | ) |  [private] | 
        
limits the twist to the allowed range
| reference | to unconstrained twist | 
Definition at line 648 of file eband_trajectory_controller.cpp.
| bool eband_local_planner::EBandTrajectoryCtrl::setBand | ( | const std::vector< Bubble > & | elastic_band | ) | 
This sets the elastic_band to the trajectory controller.
| reference | via which the band is passed | 
Definition at line 135 of file eband_trajectory_controller.cpp.
| bool eband_local_planner::EBandTrajectoryCtrl::setOdometry | ( | const nav_msgs::Odometry & | odometry | ) | 
This sets the robot velocity as provided by odometry.
| reference | via which odometry is passed | 
Definition at line 143 of file eband_trajectory_controller.cpp.
| 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
| pointer | to visualization object | 
Definition at line 128 of file eband_trajectory_controller.cpp.
| double eband_local_planner::EBandTrajectoryCtrl::sign | ( | double | n | ) |  [inline, private] | 
        
defines sign of a double
Definition at line 153 of file eband_trajectory_controller.h.
| 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] | 
        
| Transforms | twist into a given reference frame | 
| Twist | that shall be transformed | 
| refernce | to pose of frame1 | 
| reference | to pose of frame2 | 
Definition at line 623 of file eband_trajectory_controller.cpp.
double eband_local_planner::EBandTrajectoryCtrl::acc_max_ [private] | 
        
Definition at line 135 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::acc_max_rot_ [private] | 
        
Definition at line 140 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::acc_max_trans_ [private] | 
        
Definition at line 140 of file eband_trajectory_controller.h.
bool eband_local_planner::EBandTrajectoryCtrl::band_set_ [private] | 
        
Definition at line 144 of file eband_trajectory_controller.h.
pointer to costmap
Definition at line 128 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::ctrl_freq_ [private] | 
        
Definition at line 134 of file eband_trajectory_controller.h.
Definition at line 147 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::in_place_trans_vel_ [private] | 
        
Definition at line 138 of file eband_trajectory_controller.h.
bool eband_local_planner::EBandTrajectoryCtrl::initialized_ [private] | 
        
Definition at line 144 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::k_nu_ [private] | 
        
Definition at line 134 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::k_p_ [private] | 
        
Definition at line 134 of file eband_trajectory_controller.h.
geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::last_vel_ [private] | 
        
Definition at line 149 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::max_vel_lin_ [private] | 
        
Definition at line 136 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::max_vel_th_ [private] | 
        
Definition at line 136 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::min_in_place_vel_th_ [private] | 
        
Definition at line 137 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::min_vel_lin_ [private] | 
        
Definition at line 136 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::min_vel_th_ [private] | 
        
Definition at line 136 of file eband_trajectory_controller.h.
geometry_msgs::Twist eband_local_planner::EBandTrajectoryCtrl::odom_vel_ [private] | 
        
Definition at line 148 of file eband_trajectory_controller.h.
Definition at line 131 of file eband_trajectory_controller.h.
Definition at line 150 of file eband_trajectory_controller.h.
Definition at line 141 of file eband_trajectory_controller.h.
boost::shared_ptr<EBandVisualization> eband_local_planner::EBandTrajectoryCtrl::target_visual_ [private] | 
        
Definition at line 129 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::tolerance_rot_ [private] | 
        
Definition at line 139 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::tolerance_timeout_ [private] | 
        
Definition at line 139 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::tolerance_trans_ [private] | 
        
Definition at line 139 of file eband_trajectory_controller.h.
double eband_local_planner::EBandTrajectoryCtrl::virt_mass_ [private] | 
        
Definition at line 135 of file eband_trajectory_controller.h.
bool eband_local_planner::EBandTrajectoryCtrl::visualization_ [private] | 
        
Definition at line 144 of file eband_trajectory_controller.h.