44{
45
46
47
48
49
50
51
52
53
54
55
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
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
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
114 r.sleep();
115
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
130
132}
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::optional< float > maxLinearVelocity
std::optional< float > finalRadius
std::optional< float > initialAngularVelocity
std::optional< rclcpp::Duration > spiralMotionDuration
std::optional< float > linearVelocity
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmdVelPub_