controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fetch Robotics Inc
3  * Author: Michael Ferguson
4  *
5  * This program is free software: you can redistribute it and/or modify
6  * it under the terms of the GNU Lesser General Public License as published by
7  * the Free Software Foundation, either version 3 of the License, or
8  * (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU Lesser General Public License for more details.
14  *
15  * You should have received a copy of the GNU Lesser General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  */
18 
19 #ifndef FETCH_AUTO_DOCK_CONTROLLER_H
20 #define FETCH_AUTO_DOCK_CONTROLLER_H
21 
22 #include <ros/ros.h>
23 #include <tf/transform_listener.h>
24 #include <geometry_msgs/Twist.h>
25 #include <nav_msgs/Path.h>
26 
28 {
29 public:
30  explicit BaseController(ros::NodeHandle& nh);
31 
38  bool approach(const geometry_msgs::PoseStamped& target);
39 
47  bool backup(double distance, double rotate_distance);
48 
52  bool getCommand(geometry_msgs::Twist& command);
53 
55  void stop();
56 
57 private:
58  ros::Publisher cmd_vel_pub_; // Publisher of commands
59  ros::Publisher path_pub_; // Publisher of paths
60 
62  geometry_msgs::Twist command_;
63 
64  /*
65  * Parameters for approach controller
66  */
67  double k1_; // ratio in change of theta to rate of change in r
68  double k2_; // speed at which we converge to slow system
69  double min_velocity_;
70  double max_velocity_;
72  double beta_; // how fast velocity drops as k increases
73  double lambda_; // ??
74  double dist_; // used to create the tracking line
75 
76  /*
77  * Parameters for backup controller
78  */
79  geometry_msgs::PoseStamped start_;
80  bool ready_;
81  bool turning_;
82 };
83 
84 #endif // FETCH_AUTO_DOCK_CONTROLLER_H
bool approach(const geometry_msgs::PoseStamped &target)
Implements something loosely based on "A Smooth Control Law for Graceful Motion of Differential Wheel...
Definition: controller.cpp:44
void stop()
send stop command to robot base
Definition: controller.cpp:269
bool backup(double distance, double rotate_distance)
Back off dock, then rotate. Robot is first reversed by the prescribed distance, and then rotates with...
Definition: controller.cpp:173
double dist_
Definition: controller.h:74
ros::Publisher cmd_vel_pub_
Definition: controller.h:58
double max_angular_velocity_
Definition: controller.h:71
ros::Publisher path_pub_
Definition: controller.h:59
bool getCommand(geometry_msgs::Twist &command)
Get the last command sent.
Definition: controller.cpp:263
double beta_
Definition: controller.h:72
tf::TransformListener listener_
Definition: controller.h:61
ROSLIB_DECL std::string command(const std::string &cmd)
double lambda_
Definition: controller.h:73
geometry_msgs::PoseStamped start_
Definition: controller.h:79
BaseController(ros::NodeHandle &nh)
Definition: controller.cpp:28
double min_velocity_
Definition: controller.h:69
double max_velocity_
Definition: controller.h:70
geometry_msgs::Twist command_
Definition: controller.h:62


fetch_open_auto_dock
Author(s): Michael Ferguson, Griswald Brooks
autogenerated on Mon Feb 28 2022 22:21:37