SMACC2
Loading...
Searching...
No Matches
cb_position_control_free_space.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <angles/angles.h>
22#include <geometry_msgs/msg/twist.hpp>
24
27
28namespace cl_nav2z
29{
30using namespace smacc2;
32: targetYaw_(0), k_betta_(1.0), max_angular_yaw_speed_(1.0)
33{
34}
35
37
39{
40 auto nh = this->getNode();
41 cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", rclcpp::QoS(1));
42
43 cl_nav2z::CpPose * pose;
44
45 this->requiresComponent(pose, ComponentRequirement::HARD);
46
47 geometry_msgs::msg::Twist cmd_vel;
48 goalReached_ = false;
49
50 geometry_msgs::msg::Pose currentPose = pose->toPoseMsg();
51
52 rclcpp::Rate loop_rate(10);
53
54 // PID controller gains (proportional, integral, and derivative)
55 double kp_linear = 0.5;
56 double ki_linear = 0.0;
57 double kd_linear = 0.1;
58
59 double kp_angular = 0.5;
60 double ki_angular = 0.0;
61 double kd_angular = 0.1;
62
63 while (rclcpp::ok() && !goalReached_)
64 {
65 RCLCPP_INFO_STREAM_THROTTLE(
66 getLogger(), *getNode()->get_clock(), 200,
67 "CbPositionControlFreeSpace, current pose: " << currentPose.position.x << ", "
68 << currentPose.position.y << ", "
69 << tf2::getYaw(currentPose.orientation));
70
71 RCLCPP_INFO_STREAM_THROTTLE(
72 getLogger(), *getNode()->get_clock(), 200,
73 "CbPositionControlFreeSpace, target pose: " << target_pose_.position.x << ", "
74 << target_pose_.position.y << ", "
75 << tf2::getYaw(target_pose_.orientation));
76
77 tf2::Quaternion q;
78 currentPose = pose->toPoseMsg();
79
80 // Here we implement the control logic to calculate the velocity command
81 // based on the received position of the vehicle and the target pose.
82
83 // Calculate the errors in x and y
84 double error_x = target_pose_.position.x - currentPose.position.x;
85 double error_y = target_pose_.position.y - currentPose.position.y;
86
87 // Calculate the distance to the target pose
88 double distance_to_target = std::sqrt(error_x * error_x + error_y * error_y);
89
90 RCLCPP_INFO_STREAM(
91 getLogger(), "[" << getName() << "] distance to target: " << distance_to_target
92 << " ( th: " << threshold_distance_ << ")");
93
94 // Check if the robot has reached the target pose
95 if (distance_to_target < threshold_distance_)
96 {
97 RCLCPP_INFO(getLogger(), "Goal reached!");
98 // Stop the robot by setting the velocity commands to zero
99 geometry_msgs::msg::Twist cmd_vel_msg;
100 cmd_vel_msg.linear.x = 0.0;
101 cmd_vel_msg.angular.z = 0.0;
102 cmd_vel_pub_->publish(cmd_vel_msg);
103 break;
104 }
105 else
106 {
107 // Calculate the desired orientation angle
108 double desired_yaw = std::atan2(error_y, error_x);
109
110 // Calculate the difference between the desired orientation and the
111 // current orientation
112 double yaw_error = desired_yaw - (tf2::getYaw(currentPose.orientation) + M_PI);
113
114 // Ensure the yaw error is within the range [-pi, pi]
115 while (yaw_error > M_PI) yaw_error -= 2 * M_PI;
116 while (yaw_error < -M_PI) yaw_error += 2 * M_PI;
117
118 // Calculate the control signals (velocity commands) using PID controllers
119 double cmd_linear_x = kp_linear * distance_to_target + ki_linear * integral_linear_ +
120 kd_linear * (distance_to_target - prev_error_linear_);
121 double cmd_angular_z = kp_angular * yaw_error + ki_angular * integral_angular_ +
122 kd_angular * (yaw_error - prev_error_angular_);
123
124 if (cmd_linear_x > max_linear_velocity)
125 cmd_linear_x = max_linear_velocity;
126 else if (cmd_linear_x < -max_linear_velocity)
127 cmd_linear_x = -max_linear_velocity;
128
129 if (cmd_angular_z > max_angular_velocity)
130 cmd_angular_z = max_angular_velocity;
131 else if (cmd_angular_z < -max_angular_velocity)
132 cmd_angular_z = -max_angular_velocity;
133
134 // Construct and publish the velocity command message
135 geometry_msgs::msg::Twist cmd_vel_msg;
136
137 cmd_vel_msg.linear.x = cmd_linear_x;
138 cmd_vel_msg.angular.z = cmd_angular_z;
139
140 cmd_vel_pub_->publish(cmd_vel_msg);
141
142 // Update errors and integrals for the next control cycle
143 prev_error_linear_ = distance_to_target;
144 prev_error_angular_ = yaw_error;
145 integral_linear_ += distance_to_target;
146 integral_angular_ += yaw_error;
147
148 // tf2::fromMsg(currentPose.orientation, q);
149 // auto currentYaw = tf2::getYaw(currentPose.orientation);
150 // auto deltaAngle = angles::shortest_angular_distance(prevyaw,
151 // currentYaw); countAngle += deltaAngle;
152
153 // prevyaw = currentYaw;
154 // double angular_error = targetYaw_ - countAngle;
155
156 // auto omega = angular_error * k_betta_;
157 // cmd_vel.linear.x = 0;
158 // cmd_vel.linear.y = 0;
159 // cmd_vel.linear.z = 0;
160 // cmd_vel.angular.z =
161 // std::min(std::max(omega, -fabs(max_angular_yaw_speed_)),
162 // fabs(max_angular_yaw_speed_));
163
164 // RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] delta angle: "
165 // << deltaAngle); RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "]
166 // cummulated angle: " << countAngle); RCLCPP_INFO_STREAM(getLogger(), "["
167 // << getName() << "] k_betta_: " << k_betta_);
168
169 // RCLCPP_INFO_STREAM(
170 // getLogger(), "[" << getName() << "] angular error: " << angular_error
171 // << "("
172 // << yaw_goal_tolerance_rads_ << ")");
173 // RCLCPP_INFO_STREAM(
174 // getLogger(), "[" << getName() << "] command angular speed: " <<
175 // cmd_vel.angular.z);
176
177 // if (fabs(angular_error) < yaw_goal_tolerance_rads_)
178 // {
179 // RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] GOAL REACHED.
180 // Sending stop command."); goalReached_ = true; cmd_vel.linear.x = 0;
181 // cmd_vel.angular.z = 0;
182 // break;
183 // }
184
185 // this->cmd_vel_pub_->publish(cmd_vel);
186
187 loop_rate.sleep();
188 }
189 }
190
191 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Finished behavior execution");
192
193 this->postSuccessEvent();
194}
195
197
198} // namespace cl_nav2z
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_