SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
cl_px4_mr
include
cl_px4_mr
client_behaviors
cb_spiral_pattern.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
21
namespace
cl_px4_mr
22
{
23
24
class
CpTrajectorySetpoint;
25
class
CpVehicleLocalPosition;
26
27
class
CbSpiralPattern
:
public
smacc2::SmaccAsyncClientBehavior
,
public
smacc2::ISmaccUpdatable
28
{
29
public
:
30
CbSpiralPattern
(
31
float
centerX,
float
centerY,
float
altitude,
float
maxRadius = 20.0f,
float
spacing = 3.0f,
32
float
speed = 2.0f);
33
34
void
onEntry
()
override
;
35
void
onExit
()
override
;
36
void
update
()
override
;
37
38
private
:
39
float
centerX_
;
40
float
centerY_
;
41
float
altitude_
;
42
float
maxRadius_
;
43
float
spacing_
;
44
float
speed_
;
45
46
float
theta_
= 0.0f;
47
std::chrono::steady_clock::time_point
lastUpdateTime_
;
48
49
CpTrajectorySetpoint
*
trajectorySetpoint_
=
nullptr
;
50
CpVehicleLocalPosition
*
localPosition_
=
nullptr
;
51
};
52
53
}
// namespace cl_px4_mr
cl_px4_mr::CbSpiralPattern
Definition
cb_spiral_pattern.hpp:28
cl_px4_mr::CbSpiralPattern::spacing_
float spacing_
Definition
cb_spiral_pattern.hpp:43
cl_px4_mr::CbSpiralPattern::altitude_
float altitude_
Definition
cb_spiral_pattern.hpp:41
cl_px4_mr::CbSpiralPattern::localPosition_
CpVehicleLocalPosition * localPosition_
Definition
cb_spiral_pattern.hpp:50
cl_px4_mr::CbSpiralPattern::maxRadius_
float maxRadius_
Definition
cb_spiral_pattern.hpp:42
cl_px4_mr::CbSpiralPattern::onExit
void onExit() override
Definition
cb_spiral_pattern.cpp:53
cl_px4_mr::CbSpiralPattern::trajectorySetpoint_
CpTrajectorySetpoint * trajectorySetpoint_
Definition
cb_spiral_pattern.hpp:49
cl_px4_mr::CbSpiralPattern::lastUpdateTime_
std::chrono::steady_clock::time_point lastUpdateTime_
Definition
cb_spiral_pattern.hpp:47
cl_px4_mr::CbSpiralPattern::theta_
float theta_
Definition
cb_spiral_pattern.hpp:46
cl_px4_mr::CbSpiralPattern::centerX_
float centerX_
Definition
cb_spiral_pattern.hpp:39
cl_px4_mr::CbSpiralPattern::onEntry
void onEntry() override
Definition
cb_spiral_pattern.cpp:33
cl_px4_mr::CbSpiralPattern::CbSpiralPattern
CbSpiralPattern(float centerX, float centerY, float altitude, float maxRadius=20.0f, float spacing=3.0f, float speed=2.0f)
Definition
cb_spiral_pattern.cpp:22
cl_px4_mr::CbSpiralPattern::speed_
float speed_
Definition
cb_spiral_pattern.hpp:44
cl_px4_mr::CbSpiralPattern::update
void update() override
Definition
cb_spiral_pattern.cpp:55
cl_px4_mr::CbSpiralPattern::centerY_
float centerY_
Definition
cb_spiral_pattern.hpp:40
cl_px4_mr::CpTrajectorySetpoint
Definition
cp_trajectory_setpoint.hpp:29
cl_px4_mr::CpVehicleLocalPosition
Definition
cp_vehicle_local_position.hpp:26
smacc2::ISmaccUpdatable
Definition
smacc_updatable.hpp:33
smacc2::SmaccAsyncClientBehavior
Definition
smacc_asynchronous_client_behavior.hpp:56
cl_px4_mr
Definition
cl_px4_mr.hpp:29
smacc.hpp
Generated by
1.12.0