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 <tuw_nav_msgs/ControllerState.h>
8 #include <nav_msgs/Path.h>
9 #include <std_msgs/String.h>
10 
12 #include <memory>
13 
14 namespace velocity_controller
15 {
17 {
18  //special class-member functions.
19 public:
26 
29  std::unique_ptr<ros::Rate> rate_;
30 
31 private:
37  float max_vel_v_;
38  float max_vel_w_;
39  float goal_r_;
40  float Kp_val_;
41  float Ki_val_;
42  float Kd_val_;
44  void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose);
45  void subPathCb(const nav_msgs::Path::ConstPtr &_path);
46  void subCtrlCb(const std_msgs::String _cmd);
47  void publishState();
48 
49  geometry_msgs::Twist cmd_;
50  tuw_nav_msgs::ControllerState ctrl_state_;
51 };
52 
53 } // namespace velocity_controller
54 
55 #endif // CONTROLLER_NODE_H
velocity_controller::ControllerNode::subPose_
ros::Subscriber subPose_
Definition: controller_node.h:34
ros::Publisher
velocity_controller::ControllerNode::pubState_
ros::Publisher pubState_
Definition: controller_node.h:33
velocity_controller::ControllerNode::max_vel_w_
float max_vel_w_
Definition: controller_node.h:38
ros.h
velocity_controller::ControllerNode::publishState
void publishState()
Definition: controller_node.cpp:98
velocity_controller::ControllerNode::subCtrlCb
void subCtrlCb(const std_msgs::String _cmd)
Definition: controller_node.cpp:163
velocity_controller::ControllerNode::n_
ros::NodeHandle n_
Node handler to the root node.
Definition: controller_node.h:27
velocity_controller::ControllerNode::cmd_
geometry_msgs::Twist cmd_
Definition: controller_node.h:49
velocity_controller::ControllerNode::subPathCb
void subPathCb(const nav_msgs::Path::ConstPtr &_path)
Definition: controller_node.cpp:109
velocity_controller::ControllerNode::Kd_val_
float Kd_val_
Definition: controller_node.h:42
controller.h
velocity_controller::ControllerNode::n_param_
ros::NodeHandle n_param_
Node handler to the current node.
Definition: controller_node.h:28
velocity_controller::ControllerNode
Definition: controller_node.h:16
velocity_controller::ControllerNode::max_vel_v_
float max_vel_v_
Definition: controller_node.h:37
velocity_controller::ControllerNode::Ki_val_
float Ki_val_
Definition: controller_node.h:41
velocity_controller::ControllerNode::Kp_val_
float Kp_val_
Definition: controller_node.h:40
velocity_controller
Definition: controller.h:11
velocity_controller::ControllerNode::ControllerNode
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
Definition: controller_node.cpp:26
velocity_controller::ControllerNode::rate_
std::unique_ptr< ros::Rate > rate_
Definition: controller_node.h:29
velocity_controller::ControllerNode::subPath_
ros::Subscriber subPath_
Definition: controller_node.h:35
ros::Time
velocity_controller::ControllerNode::subPoseCb
void subPoseCb(const geometry_msgs::PoseWithCovarianceStampedConstPtr &_pose)
Definition: controller_node.cpp:68
velocity_controller::ControllerNode::goal_r_
float goal_r_
Definition: controller_node.h:39
velocity_controller::ControllerNode::subCtrl_
ros::Subscriber subCtrl_
Definition: controller_node.h:36
velocity_controller::Controller
Definition: controller.h:30
velocity_controller::ControllerNode::pubCmdVel_
ros::Publisher pubCmdVel_
Definition: controller_node.h:32
velocity_controller::ControllerNode::ctrl_state_
tuw_nav_msgs::ControllerState ctrl_state_
Definition: controller_node.h:50
ros::NodeHandle
ros::Subscriber
velocity_controller::ControllerNode::last_update_
ros::Time last_update_
Definition: controller_node.h:43


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:09:58