controller_node.h
Go to the documentation of this file.
1 #ifndef CONTROLLER_NODE_H
2 #define CONTROLLER_NODE_H
3 
4 #include <ros/ros.h>
5 #include <geometry_msgs/Twist.h>
6 #include <geometry_msgs/PoseWithCovarianceStamped.h>
7 #include <nav_msgs/Path.h>
8 #include <std_msgs/String.h>
9 
11 #include <memory>
12 
13 namespace velocity_controller
14 {
16 {
17  //special class-member functions.
18 public:
25 
28  std::unique_ptr<ros::Rate> rate_;
29 
30 private:
35  std::string topic_cmdVel_;
36  std::string topic_pose_;
37  std::string topic_path_;
38  std::string topic_ctrl_;
39  float max_vel_v_;
40  float max_vel_w_;
41  float goal_r_;
42  float Kp_val_;
43  float Ki_val_;
44  float Kd_val_;
46  void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose);
47  void subPathCb(const nav_msgs::Path::ConstPtr &_path);
48  void subCtrlCb(const std_msgs::String _cmd);
49 };
50 
51 } // namespace velocity_controller
52 
53 #endif // CONTROLLER_NODE_H
ros::NodeHandle n_param_
Node handler to the current node.
std::unique_ptr< ros::Rate > rate_
void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
void subPathCb(const nav_msgs::Path::ConstPtr &_path)
void subCtrlCb(const std_msgs::String _cmd)
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
ros::NodeHandle n_
Node handler to the root node.


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:29