eband_trajectory_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2010, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Christian Connette
36  *********************************************************************/
37 
38 #ifndef EBAND_TRAJECTORY_CONTROLLER_H_
39 #define EBAND_TRAJECTORY_CONTROLLER_H_
40 
41 #include <ros/ros.h>
42 #include <ros/assert.h>
43 
44 // classes which are part of this package
47 #include <eband_local_planner/EBandPlannerConfig.h>
48 
49 // geometry_msg
50 #include <geometry_msgs/PoseStamped.h>
51 #include <geometry_msgs/Pose.h>
52 #include <geometry_msgs/Pose2D.h>
53 #include <geometry_msgs/Twist.h>
54 
55 // nav_msgs
56 #include <nav_msgs/Odometry.h>
57 
58 // geometry
59 #include <angles/angles.h>
60 #include <tf/tf.h>
61 
62 // PID control library
63 #include <control_toolbox/pid.h>
64 
65 namespace eband_local_planner{
66 
72 
73  public:
74 
79 
85  EBandTrajectoryCtrl(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
86 
91 
97  void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
98 
99 
104  void reconfigure(EBandPlannerConfig& config);
105 
111 
116  bool setBand(const std::vector<Bubble>& elastic_band);
117 
122  bool setOdometry(const nav_msgs::Odometry& odometry);
123 
128  bool getTwist(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
129  bool getTwistDifferentialDrive(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
130 
131  private:
132 
133  // pointer to external objects (do NOT delete object)
135  boost::shared_ptr<EBandVisualization> target_visual_; // pointer to visualization object
136 
138 
139  // parameters
148  double rotation_correction_threshold_; // We'll do rotation correction if we're at least this far from the goal
149 
150  // diff drive only parameters
155 
156  // flags
158 
159  // data
160  std::vector<Bubble> elastic_band_;
161  geometry_msgs::Twist odom_vel_;
162  geometry_msgs::Twist last_vel_;
163  geometry_msgs::Pose ref_frame_band_;
164 
166  inline double sign(double n)
167  {
168  return n < 0.0 ? -1.0 : 1.0;
169  }
170 
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);
180 
188  geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist, const geometry_msgs::Pose& frame1,
189  const geometry_msgs::Pose& frame2);
190 
196  geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
197 
204  double getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir);
205 
206  };
207 };
208 #endif
209 
210 
211 
212 
213 
214 
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)
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.
bool setOdometry(const nav_msgs::Odometry &odometry)
This sets the robot velocity as provided by odometry.
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.
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


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Sat Feb 22 2020 04:03:28