SMACC2
Loading...
Searching...
No Matches
cp_vehicle_command.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 <px4_msgs/msg/vehicle_command.hpp>
18#include <rclcpp/rclcpp.hpp>
19#include <smacc2/smacc.hpp>
20
21namespace cl_px4_mr
22{
23
25{
26public:
28 virtual ~CpVehicleCommand();
29
30 void onInitialize() override;
31
32 void sendCommand(
33 uint32_t command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f,
34 float param4 = 0.0f, double param5 = 0.0, double param6 = 0.0, float param7 = 0.0f);
35
36 void arm();
37 void forceArm();
38 void disarm();
39 void setOffboardMode();
40 void land();
41 void takeoff(float altitude);
42
43private:
44 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr publisher_;
45};
46
47} // namespace cl_px4_mr
void sendCommand(uint32_t command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f)
rclcpp::Publisher< px4_msgs::msg::VehicleCommand >::SharedPtr publisher_