diff_drive_pose_controller_ros.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Marcus Liebhardt, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*****************************************************************************
31  ** Ifdefs
32  *****************************************************************************/
33 
34 #ifndef YOCS_DIFF_DRIVE_POSE_CONTROLLER_ROS_HPP_
35 #define YOCS_DIFF_DRIVE_POSE_CONTROLLER_ROS_HPP_
36 
37 /*****************************************************************************
38  ** Includes
39  *****************************************************************************/
40 #include <ros/ros.h>
41 #include <std_msgs/Empty.h>
42 #include <std_msgs/Float32.h>
43 #include <std_msgs/String.h>
44 #include <tf/transform_listener.h>
45 
47 
48 namespace yocs
49 {
50 
77 {
78 public:
79  DiffDrivePoseControllerROS(ros::NodeHandle& nh, std::string& name) :
80  DiffDrivePoseController(name, 0.5, M_PI / 4 * 0.5), nh_(nh)
81  {
82  }
83  ;
85  {
86  }
87  ;
88 
93  bool init();
94 
98  void spinOnce();
99 
100 private:
104  bool getPoseDiff();
105 
109  virtual void onGoalReached();
110 
115  void setControlOutput();
116 
121  void controlMaxVelCB(const std_msgs::Float32ConstPtr msg);
122 
127  void enableCB(const std_msgs::StringConstPtr msg);
128 
133  void disableCB(const std_msgs::EmptyConstPtr msg);
134 
135  // basics
137  std::string name_;
138 
139  // interfaces
150 
156  std::string base_frame_name_;
158  std::string goal_frame_name_;
159 };
160 
161 } // namespace yocs
162 
163 #endif /* YOCS_DIFF_DRIVE_POSE_CONTROLLER_ROS_HPP_ */
ros::Subscriber disable_controller_subscriber_
subscriber for disabling the controller
bool init()
Set-up necessary publishers/subscribers and variables.
A controller for driving a differential drive base to a pose goal or along a path specified by multip...
bool getPoseDiff()
Determines the pose difference in polar coordinates.
DiffDrivePoseControllerROS(ros::NodeHandle &nh, std::string &name)
tf::TransformListener tf_listener_
tf used to get goal pose relative to the base pose
ros::Subscriber enable_controller_subscriber_
subscriber for enabling the controller
void setControlOutput()
Calculates the controller output based on the current pose difference.
std::string base_frame_name_
frame name of the base
tf::StampedTransform tf_goal_pose_rel_
transform for the goal pose relative to the base pose
A controller for driving a differential drive base to a pose goal or along a path specified by multip...
void controlMaxVelCB(const std_msgs::Float32ConstPtr msg)
Callback for updating the controller&#39;s maximum linear control velocity.
void spinOnce()
Calculates velocity commands to move the diff-drive base to the (next) pose goal. ...
virtual void onGoalReached()
Publishes goal is reached message.
ros::Publisher pose_reached_publisher_
publishes the status of the goal pose tracking
ros::Publisher command_velocity_publisher_
publisher for sending out base velocity commands
std::string goal_frame_name_
frame name of the goal (pose)
ros::Subscriber control_velocity_subscriber_
subscriber for setting the controller&#39;s linear velocity
void enableCB(const std_msgs::StringConstPtr msg)
Callback for enabling the controler.
void disableCB(const std_msgs::EmptyConstPtr msg)
Callback for disabling the controler.


yocs_diff_drive_pose_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:53:50