SMACC2
Loading...
Searching...
No Matches
cb_pure_spinning.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>
25#include <sensor_msgs/msg/laser_scan.hpp>
26namespace cl_nav2z
27{
28
29CbPureSpinning::CbPureSpinning(double targetYaw_rads, double max_angular_yaw_speed)
30: targetYaw__rads(targetYaw_rads),
31 k_betta_(1.0),
32 max_angular_yaw_speed_(max_angular_yaw_speed),
33 yaw_goal_tolerance_rads_(0.1)
34{
35}
36
38
40{
41 auto nh = this->getNode();
42 cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", rclcpp::QoS(1));
43
44 cl_nav2z::Pose * pose;
45 this->requiresComponent(pose);
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 double countAngle = 0;
54 auto prevyaw = tf2::getYaw(currentPose.orientation);
55 while (rclcpp::ok() && !goalReached_)
56 {
57 tf2::Quaternion q;
58 currentPose = pose->toPoseMsg();
59 tf2::fromMsg(currentPose.orientation, q);
60 auto currentYaw = tf2::getYaw(currentPose.orientation);
61 auto deltaAngle = angles::shortest_angular_distance(prevyaw, currentYaw);
62 countAngle += deltaAngle;
63
64 prevyaw = currentYaw;
65 double angular_error = targetYaw__rads - countAngle;
66
67 auto omega = angular_error * k_betta_;
68 cmd_vel.linear.x = 0;
69 cmd_vel.linear.y = 0;
70 cmd_vel.linear.z = 0;
71 cmd_vel.angular.z =
72 std::min(std::max(omega, -fabs(max_angular_yaw_speed_)), fabs(max_angular_yaw_speed_));
73
74 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] delta angle: " << deltaAngle);
75 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] cummulated angle: " << countAngle);
76 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] k_betta_: " << k_betta_);
77
78 RCLCPP_INFO_STREAM(
79 getLogger(), "[" << getName() << "] angular error: " << angular_error << "("
80 << yaw_goal_tolerance_rads_ << ")");
81 RCLCPP_INFO_STREAM(
82 getLogger(), "[" << getName() << "] command angular speed: " << cmd_vel.angular.z);
83
84 if (fabs(angular_error) < yaw_goal_tolerance_rads_)
85 {
86 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] GOAL REACHED. Sending stop command.");
87 goalReached_ = true;
88 cmd_vel.linear.x = 0;
89 cmd_vel.angular.z = 0;
90 break;
91 }
92
93 this->cmd_vel_pub_->publish(cmd_vel);
94
95 loop_rate.sleep();
96 }
97
98 this->postSuccessEvent();
99}
100
102} // namespace cl_nav2z
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
CbPureSpinning(double targetYaw_rads, double max_angular_yaw_speed=0.5)
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_