AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
takeoff.cpp
1// Copyright 2024 Robin Müller
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#include "auto_apms_px4_interfaces/action/takeoff.hpp"
16
17#include "auto_apms_px4/mode_executor.hpp"
18#include "px4_msgs/msg/vehicle_global_position.hpp"
19#include "px4_ros2/utils/message_version.hpp"
20
21namespace auto_apms_px4
22{
23
24class TakeoffSkill : public ModeExecutor<auto_apms_px4_interfaces::action::Takeoff>
25{
26public:
27 explicit TakeoffSkill(const rclcpp::NodeOptions & options)
28 : ModeExecutor(_AUTO_APMS_PX4__TAKEOFF_ACTION_NAME, options, FlightMode::Takeoff)
29 {
30 vehicle_global_position_sub_ptr_ = this->node_ptr_->create_subscription<px4_msgs::msg::VehicleGlobalPosition>(
31 "fmu/out/vehicle_global_position" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleGlobalPosition>(),
32 rclcpp::SensorDataQoS(), [this](const px4_msgs::msg::VehicleGlobalPosition::SharedPtr msg_ptr) {
33 last_vehicle_global_position_ = std::move(*msg_ptr);
34 });
35 }
36
37private:
38 bool sendActivationCommand(const VehicleCommandClient & client, std::shared_ptr<const Goal> goal_ptr) override final
39 {
40 float target_altitude = goal_ptr->alt;
41 if (!goal_ptr->use_amsl) {
42 target_altitude += last_vehicle_global_position_.alt;
43 }
44 RCLCPP_DEBUG(
45 node_ptr_->get_logger(), "Target altitude: %f m (AMSL) - Heading: %f rad", target_altitude,
46 goal_ptr->heading_rad);
47 return client.takeoff(target_altitude, goal_ptr->heading_rad);
48 }
49
50 rclcpp::Subscription<px4_msgs::msg::VehicleGlobalPosition>::SharedPtr vehicle_global_position_sub_ptr_;
51 px4_msgs::msg::VehicleGlobalPosition last_vehicle_global_position_;
52};
53
54} // namespace auto_apms_px4
55
56#include "rclcpp_components/register_node_macro.hpp"
57RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::TakeoffSkill)
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action...
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.
Definition mode.hpp:28