SMACC2
Loading...
Searching...
No Matches
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
 
 CbPositionControlFreeSpace ()
 
void updateParameters ()
 
void onEntry () override
 
void onExit () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
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)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 

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() [1/2]

◆ CbPositionControlFreeSpace() [2/2]

cl_nav2z::CbPositionControlFreeSpace::CbPositionControlFreeSpace ( )

Member Function Documentation

◆ onEntry() [1/2]

void cl_nav2z::CbPositionControlFreeSpace::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 38 of file cb_position_control_free_space.cpp.

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

◆ onEntry() [2/2]

void cl_nav2z::CbPositionControlFreeSpace::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

◆ onExit() [1/2]

void cl_nav2z::CbPositionControlFreeSpace::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 198 of file cb_position_control_free_space.cpp.

198{}

◆ onExit() [2/2]

void cl_nav2z::CbPositionControlFreeSpace::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

◆ updateParameters() [1/2]

void cl_nav2z::CbPositionControlFreeSpace::updateParameters ( )

Definition at line 36 of file cb_position_control_free_space.cpp.

36{}

◆ updateParameters() [2/2]

void cl_nav2z::CbPositionControlFreeSpace::updateParameters ( )

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: