SMACC2
Loading...
Searching...
No Matches
cb_spiral_pattern.cpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft 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
18
19namespace cl_px4_mr
20{
21
23 float centerX, float centerY, float altitude, float maxRadius, float spacing, float speed)
24: centerX_(centerX),
25 centerY_(centerY),
26 altitude_(altitude),
27 maxRadius_(maxRadius),
28 spacing_(spacing),
29 speed_(speed)
30{
31}
32
34{
37
38 theta_ = 0.0f;
39 lastUpdateTime_ = std::chrono::steady_clock::now();
40
41 // Initial position is the spiral center
42 float z = -altitude_; // NED: up is negative
43
44 RCLCPP_INFO(
45 getLogger(),
46 "CbSpiralPattern: starting spiral center=[%.2f, %.2f] alt=%.2f maxR=%.2f spacing=%.2f "
47 "speed=%.2f",
49
51}
52
54
56{
57 auto now = std::chrono::steady_clock::now();
58 double dt = std::chrono::duration<double>(now - lastUpdateTime_).count();
59 lastUpdateTime_ = now;
60
61 // Archimedean spiral: r(theta) = a * theta
62 // where a = spacing / (2*PI) so each revolution adds 'spacing' meters of radius
63 float a = spacing_ / (2.0f * M_PI);
64
65 // Current radius
66 float r = a * theta_;
67
68 // Adaptive angular velocity to maintain constant linear speed
69 // Arc-length speed: ds/dt = sqrt(r^2 + a^2) * dtheta/dt
70 // Solving for dtheta/dt: omega = speed / sqrt(r^2 + a^2)
71 float omega = speed_ / std::sqrt(r * r + a * a);
72
73 // Advance angle
74 theta_ += omega * dt;
75
76 // Compute new position
77 float r_new = a * theta_;
78 float x = centerX_ + r_new * std::cos(theta_);
79 float y = centerY_ + r_new * std::sin(theta_);
80 float z = -altitude_; // NED
81
82 // Yaw: face direction of travel (derivatives of Archimedean spiral)
83 // dx/dtheta = a*cos(theta) - r*sin(theta)
84 // dy/dtheta = a*sin(theta) + r*cos(theta)
85 float dxdt = a * std::cos(theta_) - r_new * std::sin(theta_);
86 float dydt = a * std::sin(theta_) + r_new * std::cos(theta_);
87 float yaw = std::atan2(dydt, dxdt);
88
90
91 // Check completion
92 if (r_new >= maxRadius_)
93 {
94 RCLCPP_INFO(
95 getLogger(), "CbSpiralPattern: max radius %.2f reached (r=%.2f) - posting success",
96 maxRadius_, r_new);
97 this->postSuccessEvent();
98 }
99}
100
101} // namespace cl_px4_mr
CpVehicleLocalPosition * localPosition_
CpTrajectorySetpoint * trajectorySetpoint_
std::chrono::steady_clock::time_point lastUpdateTime_
CbSpiralPattern(float centerX, float centerY, float altitude, float maxRadius=20.0f, float spacing=3.0f, float speed=2.0f)
void setPositionNED(float x, float y, float z, float yaw=std::numeric_limits< float >::quiet_NaN())
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)