SMACC2
Loading...
Searching...
No Matches
cb_orbit_location.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 radius, float angularVelocity, int numOrbits)
24: centerX_(centerX),
25 centerY_(centerY),
26 altitude_(altitude),
27 radius_(radius),
28 angularVelocity_(angularVelocity),
29 numOrbits_(numOrbits)
30{
31}
32
34{
37
38 // Compute starting angle from current position relative to center
39 float dx = localPosition_->getX() - centerX_;
40 float dy = localPosition_->getY() - centerY_;
41 startAngle_ = std::atan2(dy, dx);
43 lastUpdateTime_ = std::chrono::steady_clock::now();
44
45 // Command initial orbit position
46 float x = centerX_ + radius_ * std::cos(currentAngle_);
47 float y = centerY_ + radius_ * std::sin(currentAngle_);
48 float z = -altitude_; // NED: up is negative
49 float yaw = currentAngle_ + M_PI; // Face toward center
50
51 RCLCPP_INFO(
52 getLogger(), "CbOrbitLocation: starting orbit center=[%.2f, %.2f] r=%.2f alt=%.2f orbits=%d",
54
56}
57
59
61{
62 auto now = std::chrono::steady_clock::now();
63 double dt = std::chrono::duration<double>(now - lastUpdateTime_).count();
64 lastUpdateTime_ = now;
65
66 // Advance angle
68
69 // Compute new position on circle
70 float x = centerX_ + radius_ * std::cos(currentAngle_);
71 float y = centerY_ + radius_ * std::sin(currentAngle_);
72 float z = -altitude_; // NED
73 float yaw = currentAngle_ + M_PI; // Face toward center
74
76
77 // Check if we've completed the required number of orbits
78 float totalAngle = currentAngle_ - startAngle_;
79 float requiredAngle = numOrbits_ * 2.0f * M_PI;
80
81 if (totalAngle >= requiredAngle)
82 {
83 RCLCPP_INFO(getLogger(), "CbOrbitLocation: %d orbits completed - posting success", numOrbits_);
84 this->postSuccessEvent();
85 }
86}
87
88} // namespace cl_px4_mr
std::chrono::steady_clock::time_point lastUpdateTime_
CpVehicleLocalPosition * localPosition_
CbOrbitLocation(float centerX, float centerY, float altitude, float radius=5.0f, float angularVelocity=0.5f, int numOrbits=3)
CpTrajectorySetpoint * trajectorySetpoint_
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)