38 #ifndef EBAND_TRAJECTORY_CONTROLLER_H_ 39 #define EBAND_TRAJECTORY_CONTROLLER_H_ 47 #include <eband_local_planner/EBandPlannerConfig.h> 50 #include <geometry_msgs/PoseStamped.h> 51 #include <geometry_msgs/Pose.h> 52 #include <geometry_msgs/Pose2D.h> 53 #include <geometry_msgs/Twist.h> 56 #include <nav_msgs/Odometry.h> 116 bool setBand(
const std::vector<Bubble>& elastic_band);
122 bool setOdometry(
const nav_msgs::Odometry& odometry);
128 bool getTwist(geometry_msgs::Twist& twist_cmd,
bool& goal_reached);
168 return n < 0.0 ? -1.0 : 1.0;
178 geometry_msgs::Twist
getFrame1ToFrame2InRefFrame(
const geometry_msgs::Pose& frame1,
const geometry_msgs::Pose& frame2,
const geometry_msgs::Pose& ref_frame);
179 geometry_msgs::Twist
getFrame1ToFrame2InRefFrameNew(
const geometry_msgs::Pose& frame1,
const geometry_msgs::Pose& frame2,
const geometry_msgs::Pose& ref_frame);
189 const geometry_msgs::Pose& frame2);
196 geometry_msgs::Twist
limitTwist(
const geometry_msgs::Twist& twist);
204 double getBubbleTargetVel(
const int& target_bub_num,
const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir);
std::vector< Bubble > elastic_band_
bool disallow_hysteresis_
double rotation_threshold_multiplier_
geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist &curr_twist, const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2)
double bubble_velocity_multiplier_
bool getTwist(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
calculates a twist feedforward command from the current band
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...
bool setBand(const std::vector< Bubble > &elastic_band)
This sets the elastic_band to the trajectory controller.
double sign(double n)
defines sign of a double
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner.
EBandTrajectoryCtrl()
Default constructor.
bool setOdometry(const nav_msgs::Odometry &odometry)
This sets the robot velocity as provided by odometry.
double min_in_place_vel_th_
geometry_msgs::Twist last_vel_
bool differential_drive_hack_
~EBandTrajectoryCtrl()
Destructor.
geometry_msgs::Twist odom_vel_
bool getTwistDifferentialDrive(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
double in_place_trans_vel_
control_toolbox::Pid pid_
double rotation_correction_threshold_
geometry_msgs::Pose ref_frame_band_
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the elastic band class by accesing costmap and loading parameters.
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...
void setVisualization(boost::shared_ptr< EBandVisualization > target_visual)
passes a reference to the eband visualization object which can be used to visualize the band optimiza...
boost::shared_ptr< EBandVisualization > target_visual_
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
limits the twist to the allowed range
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap