SMACC2
Loading...
Searching...
No Matches
cb_orbit_location.hpp
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
15#pragma once
16
17#include <chrono>
18#include <cmath>
19#include <smacc2/smacc.hpp>
20
21namespace cl_px4_mr
22{
23
24class CpTrajectorySetpoint;
25class CpVehicleLocalPosition;
26
28{
29public:
31 float centerX, float centerY, float altitude, float radius = 5.0f, float angularVelocity = 0.5f,
32 int numOrbits = 3);
33
34 void onEntry() override;
35 void onExit() override;
36 void update() override;
37
38private:
39 float centerX_;
40 float centerY_;
41 float altitude_;
42 float radius_;
45
46 float currentAngle_ = 0.0f;
47 float startAngle_ = 0.0f;
48 std::chrono::steady_clock::time_point lastUpdateTime_;
49
52};
53
54} // 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_