SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
cl_px4_mr
include
cl_px4_mr
client_behaviors
cb_figure_eight.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
26
class
CbFigureEight
:
public
smacc2::SmaccAsyncClientBehavior
,
public
smacc2::ISmaccUpdatable
27
{
28
public
:
29
CbFigureEight
(
30
float
centerX,
float
centerY,
float
altitude,
float
size = 5.0f,
float
speed = 0.5f,
31
int
numLoops = 1);
32
33
void
onEntry
()
override
;
34
void
onExit
()
override
;
35
void
update
()
override
;
36
37
private
:
38
float
centerX_
;
39
float
centerY_
;
40
float
altitude_
;
41
float
size_
;
42
float
speed_
;
43
int
numLoops_
;
44
45
float
t_
= 0.0f;
46
std::chrono::steady_clock::time_point
lastUpdateTime_
;
47
48
CpTrajectorySetpoint
*
trajectorySetpoint_
=
nullptr
;
49
};
50
51
}
// namespace cl_px4_mr
cl_px4_mr::CbFigureEight
Definition
cb_figure_eight.hpp:27
cl_px4_mr::CbFigureEight::speed_
float speed_
Definition
cb_figure_eight.hpp:42
cl_px4_mr::CbFigureEight::update
void update() override
Definition
cb_figure_eight.cpp:53
cl_px4_mr::CbFigureEight::size_
float size_
Definition
cb_figure_eight.hpp:41
cl_px4_mr::CbFigureEight::numLoops_
int numLoops_
Definition
cb_figure_eight.hpp:43
cl_px4_mr::CbFigureEight::altitude_
float altitude_
Definition
cb_figure_eight.hpp:40
cl_px4_mr::CbFigureEight::onExit
void onExit() override
Definition
cb_figure_eight.cpp:51
cl_px4_mr::CbFigureEight::lastUpdateTime_
std::chrono::steady_clock::time_point lastUpdateTime_
Definition
cb_figure_eight.hpp:46
cl_px4_mr::CbFigureEight::centerX_
float centerX_
Definition
cb_figure_eight.hpp:38
cl_px4_mr::CbFigureEight::CbFigureEight
CbFigureEight(float centerX, float centerY, float altitude, float size=5.0f, float speed=0.5f, int numLoops=1)
Definition
cb_figure_eight.cpp:21
cl_px4_mr::CbFigureEight::centerY_
float centerY_
Definition
cb_figure_eight.hpp:39
cl_px4_mr::CbFigureEight::trajectorySetpoint_
CpTrajectorySetpoint * trajectorySetpoint_
Definition
cb_figure_eight.hpp:48
cl_px4_mr::CbFigureEight::onEntry
void onEntry() override
Definition
cb_figure_eight.cpp:32
cl_px4_mr::CbFigureEight::t_
float t_
Definition
cb_figure_eight.hpp:45
cl_px4_mr::CpTrajectorySetpoint
Definition
cp_trajectory_setpoint.hpp:29
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