SMACC2
Loading...
Searching...
No Matches
cl_nav2z::CbSpiralMotion Struct Reference

#include <cb_spiral_motion.hpp>

Inheritance diagram for cl_nav2z::CbSpiralMotion:
Inheritance graph
Collaboration diagram for cl_nav2z::CbSpiralMotion:
Collaboration graph

Public Member Functions

 CbSpiralMotion (std::optional< CbSpiralMotionOptions > options=std::nullopt)
 
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=false)
 

Private Attributes

rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmdVelPub_
 
CbSpiralMotionOptions options_
 

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 43 of file cb_spiral_motion.hpp.

Constructor & Destructor Documentation

◆ CbSpiralMotion()

cl_nav2z::CbSpiralMotion::CbSpiralMotion ( std::optional< CbSpiralMotionOptions > options = std::nullopt)

Definition at line 30 of file cb_spiral_motion.cpp.

31{
32 if (options)
33 {
34 options_ = *options;
35 }
36 else
37 {
38 // we use default options
39 options_ = CbSpiralMotionOptions();
40 }
41}
CbSpiralMotionOptions options_

References options_.

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbSpiralMotion::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 43 of file cb_spiral_motion.cpp.

44{
45 /*
46 struct CbSpiralMotionOptions
47{
48 std::optional<float> linearVelocity = 0.0f;
49 std::optional<float> maxLinearVelocity = 1.0f;
50 std::optional<float> initialAngularVelocity = 1.0f;
51 std::optional<rclcpp::Duration> spiralMotionDuration = rclcpp::Duration::from_seconds(120);
52 std::optional <float> finalRadius=10.0f;//meters
53};
54 */
55
56 auto linearVelocity = *(options_.linearVelocity);
57 auto maxLinearVelocity = *(options_.maxLinearVelocity);
58 auto initialAngularVelocity = *(options_.initialAngularVelocity);
59 auto spiralMotionDuration = *(options_.spiralMotionDuration);
60 auto finalRadius = *(options_.finalRadius);
61
62 float rate = 20.0f;
63 rclcpp::Rate r(rate);
64 cmdVelPub_ = getNode()->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", rclcpp::QoS(1));
65
66 rclcpp::Duration linearRamp = rclcpp::Duration::from_seconds(spiralMotionDuration.seconds());
67 float linearAceleration = (maxLinearVelocity - linearVelocity) / linearRamp.seconds();
68 float dt = 1.0f / rate;
69
70 // we know final radious and the constant linear velocity
71 float finalAngularVelocity = maxLinearVelocity / finalRadius;
72
73 float angularAcceleration =
74 (initialAngularVelocity - finalAngularVelocity) / spiralMotionDuration.seconds();
75
76 geometry_msgs::msg::Twist cmd_vel;
77
78 cmd_vel.linear.x = linearVelocity;
79 cmd_vel.angular.z = initialAngularVelocity;
80 auto start_time = getNode()->now();
81
82 RCLCPP_INFO_STREAM(
83 getLogger(), "[CbSpiralMotion]: initialAngularVelocity: "
84 << initialAngularVelocity << ", finalAngularVelocity: " << finalAngularVelocity
85 << ", angularAcceleration: " << angularAcceleration);
86 RCLCPP_INFO_STREAM(
87 getLogger(), "[CbSpiralMotion]: linearAceleration: "
88 << linearAceleration << ", maxLinearVelocity: " << maxLinearVelocity);
89
90 bool end_condition = false;
91
92 while (!end_condition)
93 {
94 auto current_time = getNode()->now() - start_time;
95
96 cmd_vel.linear.x += linearAceleration * dt;
97 if (cmd_vel.linear.x > maxLinearVelocity)
98 {
99 cmd_vel.linear.x = maxLinearVelocity;
100 }
101
102 float signVal = (cmd_vel.angular.z >= 0.0f) ? 1.0f : -1.0f;
103 // cmd_vel.angular.z -= signVal * angularAcceleration * dt;
104
105 float ellapsedTimeFactor = current_time.seconds() / spiralMotionDuration.seconds();
106 cmd_vel.angular.z = initialAngularVelocity * (1.0f - ellapsedTimeFactor) +
107 finalAngularVelocity * ellapsedTimeFactor;
108
109 RCLCPP_INFO(
110 getLogger(), "[CbSpiralMotion] cmd_vel.linear.x = %f, cmd_vel.angular.z = %f",
111 cmd_vel.linear.x, cmd_vel.angular.z);
112
113 cmdVelPub_->publish(cmd_vel);
114 r.sleep();
115
116 auto now = getNode()->now();
117
118 rclcpp::Duration ellapsed = now - start_time;
119 RCLCPP_INFO_STREAM(
120 getLogger(), "[CbSpiralMotion] ellapsed time: " << ellapsed.seconds() << ", total duration: "
121 << spiralMotionDuration.seconds());
122 if (ellapsed > spiralMotionDuration)
123 {
124 RCLCPP_INFO_STREAM(getLogger(), "[CbSpiralMotion] spiralMotionDuration reached");
125 end_condition = true;
126 }
127 }
128
129 // asynchronous client behaviors usually post a success event when they are done
130 // that is used in states to transition to the next state
131 this->postSuccessEvent();
132}
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::optional< float > initialAngularVelocity
std::optional< float > linearVelocity
std::optional< rclcpp::Duration > spiralMotionDuration
std::optional< float > maxLinearVelocity
std::optional< float > finalRadius
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmdVelPub_

References cmdVelPub_, cl_nav2z::CbSpiralMotionOptions::finalRadius, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), cl_nav2z::CbSpiralMotionOptions::initialAngularVelocity, cl_nav2z::CbSpiralMotionOptions::linearVelocity, cl_nav2z::CbSpiralMotionOptions::maxLinearVelocity, options_, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), and cl_nav2z::CbSpiralMotionOptions::spiralMotionDuration.

Here is the call graph for this function:

◆ onExit()

void cl_nav2z::CbSpiralMotion::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 134 of file cb_spiral_motion.cpp.

134{}

Member Data Documentation

◆ cmdVelPub_

rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cl_nav2z::CbSpiralMotion::cmdVelPub_
private

Definition at line 56 of file cb_spiral_motion.hpp.

Referenced by onEntry().

◆ options_

CbSpiralMotionOptions cl_nav2z::CbSpiralMotion::options_
private

Definition at line 59 of file cb_spiral_motion.hpp.

Referenced by CbSpiralMotion(), and onEntry().


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