SMACC2
Loading...
Searching...
No Matches
cp_trajectory_setpoint.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 <cmath>
18#include <mutex>
19#include <px4_msgs/msg/trajectory_setpoint.hpp>
20#include <rclcpp/rclcpp.hpp>
21#include <smacc2/smacc.hpp>
22
23namespace cl_px4_mr
24{
25
26class CpVehicleLocalPosition;
27
29{
30public:
32 virtual ~CpTrajectorySetpoint();
33
34 void onInitialize() override;
35
36 void setPositionNED(
37 float x, float y, float z, float yaw = std::numeric_limits<float>::quiet_NaN());
38 void hold();
39 void republishLast();
40
41 px4_msgs::msg::TrajectorySetpoint getLastSetpoint() const;
42
43private:
44 rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr publisher_;
46 px4_msgs::msg::TrajectorySetpoint lastSetpoint_;
47 mutable std::mutex mutex_;
48 bool hasPublished_ = false;
49};
50
51} // namespace cl_px4_mr
px4_msgs::msg::TrajectorySetpoint getLastSetpoint() const
px4_msgs::msg::TrajectorySetpoint lastSetpoint_
void setPositionNED(float x, float y, float z, float yaw=std::numeric_limits< float >::quiet_NaN())
rclcpp::Publisher< px4_msgs::msg::TrajectorySetpoint >::SharedPtr publisher_