local_controller_node.h
Go to the documentation of this file.
1 //
2 // Created by axelbr on 21.08.19.
3 //
4 
5 #ifndef SRC_LOCAL_CONTROLLER_NODE_H
6 #define SRC_LOCAL_CONTROLLER_NODE_H
7 
8 #include <ros/ros.h>
9 #include <geometry_msgs/Twist.h>
10 #include <geometry_msgs/PoseWithCovarianceStamped.h>
11 #include <tuw_nav_msgs/ControllerState.h>
12 #include <nav_msgs/Path.h>
13 #include <std_msgs/String.h>
14 #include <memory>
16 #include <tuw_local_controller_msgs/ExecutePathAction.h>
17 #include "controller.h"
18 
19 namespace velocity_controller {
20 
22  float max_v = 0.8;
23  float max_w = 1.0;
24  float goal_radius = 0.2;
25  float Kp = 5.0;
26  float Ki = 0.0;
27  float Kd = 1.0;
28  };
29 
31  //special class-member functions.
32  public:
39 
42  std::unique_ptr<ros::Rate> rate_;
43 
44  private:
51 
52  void onPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose);
53 
54  void onCommandReceived(const std_msgs::String command);
55 
56  void onGoalReceived(const tuw_local_controller_msgs::ExecutePathGoalConstPtr& goal);
57 
58  void publishControllerState(const nav_msgs::Path &path);
59 
60  void setupController(const nav_msgs::Path &path, const ControllerConfig& config);
61  };
62 
63 } // namespace velocity_controller
64 
65 #endif //SRC_LOCAL_CONTROLLER_NODE_H
velocity_controller::ControllerNode::command_subscriber
ros::Subscriber command_subscriber
Definition: local_controller_node.h:48
velocity_controller::ControllerConfig::Kp
float Kp
Definition: local_controller_node.h:25
velocity_controller::ControllerConfig::Ki
float Ki
Definition: local_controller_node.h:26
velocity_controller::ControllerConfig::Kd
float Kd
Definition: local_controller_node.h:27
ros::Publisher
ros.h
velocity_controller::ControllerNode::action_server
actionlib::SimpleActionServer< tuw_local_controller_msgs::ExecutePathAction > action_server
Definition: local_controller_node.h:50
velocity_controller::ControllerNode::onGoalReceived
void onGoalReceived(const tuw_local_controller_msgs::ExecutePathGoalConstPtr &goal)
Definition: local_controller_node.cpp:92
velocity_controller::ControllerNode::n_
ros::NodeHandle n_
Node handler to the root node.
Definition: controller_node.h:27
simple_action_server.h
controller.h
velocity_controller::ControllerNode::n_param_
ros::NodeHandle n_param_
Node handler to the current node.
Definition: controller_node.h:28
velocity_controller::ControllerConfig::goal_radius
float goal_radius
Definition: local_controller_node.h:24
velocity_controller::ControllerNode::twist_publisher
ros::Publisher twist_publisher
Definition: local_controller_node.h:45
velocity_controller::ControllerNode
Definition: controller_node.h:16
velocity_controller
Definition: controller.h:11
velocity_controller::ControllerNode::onCommandReceived
void onCommandReceived(const std_msgs::String command)
Definition: local_controller_node.cpp:77
velocity_controller::ControllerConfig::max_w
float max_w
Definition: local_controller_node.h:23
velocity_controller::ControllerConfig
Definition: local_controller_node.h:21
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::ControllerConfig::max_v
float max_v
Definition: local_controller_node.h:22
velocity_controller::ControllerNode::setupController
void setupController(const nav_msgs::Path &path, const ControllerConfig &config)
Definition: local_controller_node.cpp:141
velocity_controller::ControllerNode::publishControllerState
void publishControllerState(const nav_msgs::Path &path)
Definition: local_controller_node.cpp:63
ros::Time
actionlib::SimpleActionServer< tuw_local_controller_msgs::ExecutePathAction >
velocity_controller::ControllerNode::onPoseReceived
void onPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
Definition: local_controller_node.cpp:36
velocity_controller::Controller
Definition: controller.h:30
velocity_controller::ControllerNode::pose_subscriber
ros::Subscriber pose_subscriber
Definition: local_controller_node.h:47
velocity_controller::ControllerNode::state_publisher
ros::Publisher state_publisher
Definition: local_controller_node.h:46
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