Go to the documentation of this file.
5 #ifndef SRC_LOCAL_CONTROLLER_NODE_H
6 #define SRC_LOCAL_CONTROLLER_NODE_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>
16 #include <tuw_local_controller_msgs/ExecutePathAction.h>
42 std::unique_ptr<ros::Rate>
rate_;
52 void onPoseReceived(
const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose);
56 void onGoalReceived(
const tuw_local_controller_msgs::ExecutePathGoalConstPtr& goal);
65 #endif //SRC_LOCAL_CONTROLLER_NODE_H
ros::Subscriber command_subscriber
actionlib::SimpleActionServer< tuw_local_controller_msgs::ExecutePathAction > action_server
void onGoalReceived(const tuw_local_controller_msgs::ExecutePathGoalConstPtr &goal)
ros::NodeHandle n_
Node handler to the root node.
ros::NodeHandle n_param_
Node handler to the current node.
ros::Publisher twist_publisher
void onCommandReceived(const std_msgs::String command)
ControllerNode(ros::NodeHandle &n)
Construct a new Controller Node object.
std::unique_ptr< ros::Rate > rate_
void setupController(const nav_msgs::Path &path, const ControllerConfig &config)
void publishControllerState(const nav_msgs::Path &path)
void onPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
ros::Subscriber pose_subscriber
ros::Publisher state_publisher