Public Member Functions | Private Member Functions | Private Attributes
eband_local_planner::EBandTrajectoryCtrl Class Reference

#include <eband_trajectory_controller.h>

List of all members.

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::Costmap2DROScostmap_ros_
 pointer to costmap
double ctrl_freq_
std::vector< Bubbleelastic_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_

Detailed Description

Definition at line 72 of file eband_trajectory_controller.h.


Constructor & Destructor Documentation

Default constructor.

Definition at line 48 of file eband_trajectory_controller.cpp.

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 51 of file eband_trajectory_controller.cpp.

Destructor.

Definition at line 62 of file eband_trajectory_controller.cpp.


Member Function Documentation

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 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.

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 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

Parameters:
refernceto the twist cmd

Definition at line 174 of file eband_trajectory_controller.cpp.

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 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

Parameters:
referenceto unconstrained twist
Returns:
twist in allowed range

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.

Parameters:
referencevia 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.

Parameters:
referencevia which odometry is passed

Definition at line 143 of file eband_trajectory_controller.cpp.

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

Parameters:
pointerto 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]
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 623 of file eband_trajectory_controller.cpp.


Member Data Documentation

Definition at line 135 of file eband_trajectory_controller.h.

Definition at line 140 of file eband_trajectory_controller.h.

Definition at line 140 of file eband_trajectory_controller.h.

Definition at line 144 of file eband_trajectory_controller.h.

pointer to costmap

Definition at line 128 of file eband_trajectory_controller.h.

Definition at line 134 of file eband_trajectory_controller.h.

Definition at line 147 of file eband_trajectory_controller.h.

Definition at line 138 of file eband_trajectory_controller.h.

Definition at line 144 of file eband_trajectory_controller.h.

Definition at line 134 of file eband_trajectory_controller.h.

Definition at line 134 of file eband_trajectory_controller.h.

Definition at line 149 of file eband_trajectory_controller.h.

Definition at line 136 of file eband_trajectory_controller.h.

Definition at line 136 of file eband_trajectory_controller.h.

Definition at line 137 of file eband_trajectory_controller.h.

Definition at line 136 of file eband_trajectory_controller.h.

Definition at line 136 of file eband_trajectory_controller.h.

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.

Definition at line 129 of file eband_trajectory_controller.h.

Definition at line 139 of file eband_trajectory_controller.h.

Definition at line 139 of file eband_trajectory_controller.h.

Definition at line 139 of file eband_trajectory_controller.h.

Definition at line 135 of file eband_trajectory_controller.h.

Definition at line 144 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
autogenerated on Mon Oct 6 2014 02:47:28