3 #include <tuw_nav_msgs/ControllerState.h>
6 #define NSEC_2_SECS(A) ((float)A / 1000000000.0)
8 int main(
int argc,
char **argv)
10 std::string name(
"pid_controller");
27 action_server(n,
"execute_path", [&](const auto& goal) {this->onGoalReceived(goal);},
false)
29 twist_publisher = n.advertise<geometry_msgs::Twist>(
"cmd_vel", 1000);
30 state_publisher = n.advertise<tuw_nav_msgs::ControllerState>(
"state_trajectory_ctrl", 10);
31 pose_subscriber = n.subscribe(
"pose", 1000, &ControllerNode::onPoseReceived,
this);
32 command_subscriber = n.subscribe(
"ctrl", 1000, &ControllerNode::onCommandReceived,
this);
33 action_server.start();
36 void ControllerNode::onPoseReceived(
const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose){
38 pt.
x = pose->pose.pose.position.x;
39 pt.
y = pose->pose.pose.position.y;
41 tf::Quaternion q(pose->pose.pose.orientation.x, pose->pose.pose.orientation.y, pose->pose.pose.orientation.z,
42 pose->pose.pose.orientation.w);
44 double roll, pitch, yaw;
45 m.
getRPY(roll, pitch, yaw);
60 twist_publisher.publish(
command);
63 void ControllerNode::publishControllerState(
const nav_msgs::Path &path) {
64 tuw_nav_msgs::ControllerState controller_state;
65 controller_state.progress_in_relation_to = path.header.seq;
66 controller_state.header.frame_id = path.header.frame_id;
68 controller_state.progress = getProgress();
70 controller_state.state = controller_state.STATE_DRIVING;
72 controller_state.state = controller_state.STATE_IDLE;
74 state_publisher.publish(controller_state);
77 void ControllerNode::onCommandReceived(
const std_msgs::String command){
80 ROS_INFO(
"Multi Robot Controller: received %s",
s.c_str());
81 if (
s.compare(
"run") == 0) {
83 }
else if (
s.compare(
"stop") == 0) {
85 }
else if (
s.compare(
"step") == 0) {
92 void ControllerNode::onGoalReceived(
const tuw_local_controller_msgs::ExecutePathGoalConstPtr &goal) {
94 const auto& path = goal->path;
95 if (path.poses.empty()) {
100 n_param_.getParam(
"max_v",config.
max_v);
101 n_param_.getParam(
"max_w", config.
max_w);
102 n_param_.getParam(
"goal_radius", config.
goal_radius);
103 n_param_.getParam(
"Kp", config.
Kp);;
104 n_param_.getParam(
"Ki", config.
Ki);
105 n_param_.getParam(
"Kd", config.
Kd);
108 setPID(config.
Kp, config.
Ki, config.
Kd);
110 setupController(path, config);
112 tuw_local_controller_msgs::ExecutePathResult result;
113 geometry_msgs::Pose pose;
117 int progress = getProgress();
120 while (progress < goal->path.poses.size()) {
121 if (action_server.isPreemptRequested() || !
ros::ok()) {
123 action_server.setPreempted(result);
128 tuw_local_controller_msgs::ExecutePathFeedback feedback;
129 feedback.current_step = progress;
130 action_server.publishFeedback(feedback);
131 publishControllerState(path);
133 progress = getProgress();
137 action_server.setSucceeded(result,
"Robot finished path.");
141 void ControllerNode::setupController(
const nav_msgs::Path &path,
const ControllerConfig& config) {
143 auto it = path.poses.begin();
144 std::vector<PathPoint> path_points;
145 for (; it != path.poses.end(); ++it)
149 tf::Quaternion q(it->pose.orientation.x, it->pose.orientation.y, it->pose.orientation.z, it->pose.orientation.w);
151 double roll, pitch, yaw;
152 m.
getRPY(roll, pitch, yaw);
154 pt.
x = it->pose.position.x;
155 pt.
y = it->pose.position.y;
158 path_points.push_back(pt);
163 setPID(config.
Kp, config.
Ki, config.
Kd);
164 setPath(std::make_shared<std::vector<PathPoint>>(path_points));