SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Private Attributes | List of all members
cl_nav2z::CbPositionControlFreeSpace Struct Reference

#include <cb_position_control_free_space.hpp>

Inheritance diagram for cl_nav2z::CbPositionControlFreeSpace:
Inheritance graph
Collaboration diagram for cl_nav2z::CbPositionControlFreeSpace:
Collaboration graph

Public Member Functions

 CbPositionControlFreeSpace ()
 
void updateParameters ()
 
void onEntry () override
 
void onExit () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
 

Public Attributes

double yaw_goal_tolerance_rads_ = 0.1
 
double threshold_distance_ = 3.0
 
geometry_msgs::msg::Pose target_pose_
 

Private Attributes

double targetYaw_
 
bool goalReached_
 
double k_betta_
 
double max_angular_yaw_speed_
 
double prev_error_linear_ = 0.0
 
double prev_error_angular_ = 0.0
 
double integral_linear_ = 0.0
 
double integral_angular_ = 0.0
 
double max_linear_velocity = 1.0
 
double max_angular_velocity = 1.0
 
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 29 of file cb_position_control_free_space.hpp.

Constructor & Destructor Documentation

◆ CbPositionControlFreeSpace()

cl_nav2z::CbPositionControlFreeSpace::CbPositionControlFreeSpace ( )

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbPositionControlFreeSpace::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 37 of file cb_position_control_free_space.cpp.

38{
39 auto nh = this->getNode();
40 cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", rclcpp::QoS(1));
41
42 cl_nav2z::Pose * pose;
43
44 this->requiresComponent(pose);
45
46 geometry_msgs::msg::Twist cmd_vel;
47 goalReached_ = false;
48
49 geometry_msgs::msg::Pose currentPose = pose->toPoseMsg();
50
51 rclcpp::Rate loop_rate(10);
52 double countAngle = 0;
53 auto prevyaw = tf2::getYaw(currentPose.orientation);
54
55 // PID controller gains (proportional, integral, and derivative)
56 double kp_linear = 0.5;
57 double ki_linear = 0.0;
58 double kd_linear = 0.1;
59
60 double kp_angular = 0.5;
61 double ki_angular = 0.0;
62 double kd_angular = 0.1;
63
64 while (rclcpp::ok() && !goalReached_)
65 {
66 RCLCPP_INFO_STREAM_THROTTLE(
67 getLogger(), *getNode()->get_clock(), 200,
68 "CbPositionControlFreeSpace, current pose: " << currentPose.position.x << ", "
69 << currentPose.position.y << ", "
70 << tf2::getYaw(currentPose.orientation));
71
72 RCLCPP_INFO_STREAM_THROTTLE(
73 getLogger(), *getNode()->get_clock(), 200,
74 "CbPositionControlFreeSpace, target pose: " << target_pose_.position.x << ", "
75 << target_pose_.position.y << ", "
76 << tf2::getYaw(target_pose_.orientation));
77
78 tf2::Quaternion q;
79 currentPose = pose->toPoseMsg();
80
81 // Here we implement the control logic to calculate the velocity command
82 // based on the received position of the vehicle and the target pose.
83
84 // Calculate the errors in x and y
85 double error_x = target_pose_.position.x - currentPose.position.x;
86 double error_y = target_pose_.position.y - currentPose.position.y;
87
88 // Calculate the distance to the target pose
89 double distance_to_target = std::sqrt(error_x * error_x + error_y * error_y);
90
91 RCLCPP_INFO_STREAM(
92 getLogger(), "[" << getName() << "] distance to target: " << distance_to_target
93 << " ( th: " << threshold_distance_ << ")");
94
95 // Check if the robot has reached the target pose
96 if (distance_to_target < threshold_distance_)
97 {
98 RCLCPP_INFO(getLogger(), "Goal reached!");
99 // Stop the robot by setting the velocity commands to zero
100 geometry_msgs::msg::Twist cmd_vel_msg;
101 cmd_vel_msg.linear.x = 0.0;
102 cmd_vel_msg.angular.z = 0.0;
103 cmd_vel_pub_->publish(cmd_vel_msg);
104 break;
105 }
106 else
107 {
108 // Calculate the desired orientation angle
109 double desired_yaw = std::atan2(error_y, error_x);
110
111 // Calculate the difference between the desired orientation and the
112 // current orientation
113 double yaw_error = desired_yaw - (tf2::getYaw(currentPose.orientation) + M_PI);
114
115 // Ensure the yaw error is within the range [-pi, pi]
116 while (yaw_error > M_PI) yaw_error -= 2 * M_PI;
117 while (yaw_error < -M_PI) yaw_error += 2 * M_PI;
118
119 // Calculate the control signals (velocity commands) using PID controllers
120 double cmd_linear_x = kp_linear * distance_to_target + ki_linear * integral_linear_ +
121 kd_linear * (distance_to_target - prev_error_linear_);
122 double cmd_angular_z = kp_angular * yaw_error + ki_angular * integral_angular_ +
123 kd_angular * (yaw_error - prev_error_angular_);
124
125 if (cmd_linear_x > max_linear_velocity)
126 cmd_linear_x = max_linear_velocity;
127 else if (cmd_linear_x < -max_linear_velocity)
128 cmd_linear_x = -max_linear_velocity;
129
130 if (cmd_angular_z > max_angular_velocity)
131 cmd_angular_z = max_angular_velocity;
132 else if (cmd_angular_z < -max_angular_velocity)
133 cmd_angular_z = -max_angular_velocity;
134
135 // Construct and publish the velocity command message
136 geometry_msgs::msg::Twist cmd_vel_msg;
137
138 cmd_vel_msg.linear.x = cmd_linear_x;
139 cmd_vel_msg.angular.z = cmd_angular_z;
140
141 cmd_vel_pub_->publish(cmd_vel_msg);
142
143 // Update errors and integrals for the next control cycle
144 prev_error_linear_ = distance_to_target;
145 prev_error_angular_ = yaw_error;
146 integral_linear_ += distance_to_target;
147 integral_angular_ += yaw_error;
148
149 // tf2::fromMsg(currentPose.orientation, q);
150 // auto currentYaw = tf2::getYaw(currentPose.orientation);
151 // auto deltaAngle = angles::shortest_angular_distance(prevyaw,
152 // currentYaw); countAngle += deltaAngle;
153
154 // prevyaw = currentYaw;
155 // double angular_error = targetYaw_ - countAngle;
156
157 // auto omega = angular_error * k_betta_;
158 // cmd_vel.linear.x = 0;
159 // cmd_vel.linear.y = 0;
160 // cmd_vel.linear.z = 0;
161 // cmd_vel.angular.z =
162 // std::min(std::max(omega, -fabs(max_angular_yaw_speed_)),
163 // fabs(max_angular_yaw_speed_));
164
165 // RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] delta angle: "
166 // << deltaAngle); RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "]
167 // cummulated angle: " << countAngle); RCLCPP_INFO_STREAM(getLogger(), "["
168 // << getName() << "] k_betta_: " << k_betta_);
169
170 // RCLCPP_INFO_STREAM(
171 // getLogger(), "[" << getName() << "] angular error: " << angular_error
172 // << "("
173 // << yaw_goal_tolerance_rads_ << ")");
174 // RCLCPP_INFO_STREAM(
175 // getLogger(), "[" << getName() << "] command angular speed: " <<
176 // cmd_vel.angular.z);
177
178 // if (fabs(angular_error) < yaw_goal_tolerance_rads_)
179 // {
180 // RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] GOAL REACHED.
181 // Sending stop command."); goalReached_ = true; cmd_vel.linear.x = 0;
182 // cmd_vel.angular.z = 0;
183 // break;
184 // }
185
186 // this->cmd_vel_pub_->publish(cmd_vel);
187
188 loop_rate.sleep();
189 }
190 }
191
192 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Finished behavior execution");
193
194 this->postSuccessEvent();
195}
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_

References cmd_vel_pub_, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), goalReached_, integral_angular_, integral_linear_, max_angular_velocity, max_linear_velocity, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), prev_error_angular_, prev_error_linear_, smacc2::ISmaccClientBehavior::requiresComponent(), target_pose_, and threshold_distance_.

Referenced by cl_nav2z::CbNavigateNextWaypointFree::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onExit()

void cl_nav2z::CbPositionControlFreeSpace::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 197 of file cb_position_control_free_space.cpp.

197{}

◆ updateParameters()

void cl_nav2z::CbPositionControlFreeSpace::updateParameters ( )

Definition at line 35 of file cb_position_control_free_space.cpp.

35{}

Member Data Documentation

◆ cmd_vel_pub_

rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cl_nav2z::CbPositionControlFreeSpace::cmd_vel_pub_
private

Definition at line 47 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ goalReached_

bool cl_nav2z::CbPositionControlFreeSpace::goalReached_
private

Definition at line 33 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ integral_angular_

double cl_nav2z::CbPositionControlFreeSpace::integral_angular_ = 0.0
private

Definition at line 40 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ integral_linear_

double cl_nav2z::CbPositionControlFreeSpace::integral_linear_ = 0.0
private

Definition at line 39 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ k_betta_

double cl_nav2z::CbPositionControlFreeSpace::k_betta_
private

Definition at line 34 of file cb_position_control_free_space.hpp.

◆ max_angular_velocity

double cl_nav2z::CbPositionControlFreeSpace::max_angular_velocity = 1.0
private

Definition at line 45 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ max_angular_yaw_speed_

double cl_nav2z::CbPositionControlFreeSpace::max_angular_yaw_speed_
private

Definition at line 35 of file cb_position_control_free_space.hpp.

◆ max_linear_velocity

double cl_nav2z::CbPositionControlFreeSpace::max_linear_velocity = 1.0
private

Definition at line 44 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ prev_error_angular_

double cl_nav2z::CbPositionControlFreeSpace::prev_error_angular_ = 0.0
private

Definition at line 38 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ prev_error_linear_

double cl_nav2z::CbPositionControlFreeSpace::prev_error_linear_ = 0.0
private

Definition at line 37 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ target_pose_

geometry_msgs::msg::Pose cl_nav2z::CbPositionControlFreeSpace::target_pose_

◆ targetYaw_

double cl_nav2z::CbPositionControlFreeSpace::targetYaw_
private

Definition at line 32 of file cb_position_control_free_space.hpp.

◆ threshold_distance_

double cl_nav2z::CbPositionControlFreeSpace::threshold_distance_ = 3.0

Definition at line 52 of file cb_position_control_free_space.hpp.

Referenced by onEntry().

◆ yaw_goal_tolerance_rads_

double cl_nav2z::CbPositionControlFreeSpace::yaw_goal_tolerance_rads_ = 0.1

Definition at line 50 of file cb_position_control_free_space.hpp.


The documentation for this struct was generated from the following files: