PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
waypoint_trajectory_executor.hpp
1/****************************************************************************
2 * Copyright (c) 2024 PX4 Development Team.
3 * SPDX-License-Identifier: BSD-3-Clause
4 ****************************************************************************/
5
6#pragma once
7#include <memory>
8#include <optional>
9#include <px4_ros2/components/mode.hpp>
10#include <px4_ros2/control/setpoint_types/multicopter/goto.hpp>
11#include <px4_ros2/mission/mission.hpp>
12#include <px4_ros2/mission/trajectory/trajectory_executor.hpp>
13#include <px4_ros2/odometry/attitude.hpp>
14#include <px4_ros2/odometry/global_position.hpp>
15#include <rclcpp/rclcpp.hpp>
16
21namespace px4_ros2::multicopter {
27 public:
28 explicit WaypointTrajectoryExecutor(ModeBase& mode, float acceptance_radius = 2.0f);
29
30 ~WaypointTrajectoryExecutor() override = default;
31
32 bool navigationItemTypeSupported(NavigationItemType type) override;
33 bool frameSupported(MissionFrame frame) override;
34 void runTrajectory(const TrajectoryConfig& config) override;
35 void updateSetpoint() override;
36
37 private:
38 void continueNextItem();
39 bool positionReached(const Eigen::Vector3d& target_position_m, float acceptance_radius) const;
40 bool headingReached(float target_heading_rad) const;
41
42 TrajectoryConfig _current_trajectory;
43 const float _acceptance_radius;
44 std::shared_ptr<OdometryGlobalPosition> _vehicle_global_position;
45 std::shared_ptr<OdometryAttitude> _vehicle_attitude;
46 std::shared_ptr<MulticopterGotoGlobalSetpointType> _setpoint;
47 std::optional<int> _current_index;
48 rclcpp::Node& _node;
49};
50
51} // namespace px4_ros2::multicopter
Base class for a mode.
Definition mode.hpp:73
Interface for a trajectory executor.
Definition trajectory_executor.hpp:20
Trajectory executor using goto setpoints.
Definition waypoint_trajectory_executor.hpp:26
Definition trajectory_executor.hpp:29