AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
goto.cpp
Go to the documentation of this file.
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// https://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 "px4_ros2/control/setpoint_types/goto.hpp"
16
17#include <Eigen/Core>
18
19#include "auto_apms_interfaces/action/go_to.hpp"
22#include "px4_ros2/utils/geodesic.hpp"
23#include "tf2_eigen/tf2_eigen.hpp"
24
25namespace auto_apms_px4
26{
27
28using GoToActionType = auto_apms_interfaces::action::GoTo;
29
30class GoToMode : public PositionAwareMode<GoToActionType>
31{
32 std::shared_ptr<px4_ros2::GotoGlobalSetpointType> goto_setpoint_ptr_;
33 Eigen::Vector3d position_target_f_glob_;
34 float heading_target_rad_;
35
36public:
37 GoToMode(rclcpp::Node& node, const px4_ros2::ModeBase::Settings& settings, const std::string& topic_namespace_prefix,
38 std::shared_ptr<ActionContextType> action_context_ptr)
39 : PositionAwareMode{ node, settings, topic_namespace_prefix, action_context_ptr }
40 {
41 goto_setpoint_ptr_ = std::make_shared<px4_ros2::GotoGlobalSetpointType>(*this);
42 }
43
44private:
45 void OnActivateWithGoal(std::shared_ptr<const Goal> goal_ptr) final
46 {
47 position_target_f_glob_ = Eigen::Vector3d(goal_ptr->lat, goal_ptr->lon, goal_ptr->alt);
48
49 // Heading target has to be in rad clockwise from north
50 if (goal_ptr->head_towards_destination)
51 {
52 // Heading target needs to be in interval [-pi, pi] (from north)
53 heading_target_rad_ =
54 px4_ros2::headingToGlobalPosition(vehicle_global_position_ptr_->position(), position_target_f_glob_);
55 }
56 else
57 {
58 heading_target_rad_ = goal_ptr->heading_clockwise_from_north_rad;
59 }
60
61 auto double_to_string = [](double num, int decimals) {
62 std::stringstream stream;
63 stream << std::fixed << std::setprecision(decimals) << num;
64 return stream.str();
65 };
66
67 RCLCPP_DEBUG(node().get_logger(), "GoTo target: Position: [%s°, %s°, %sm] - Heading: %f",
68 double_to_string(position_target_f_glob_.x(), 10).c_str(),
69 double_to_string(position_target_f_glob_.y(), 10).c_str(),
70 double_to_string(position_target_f_glob_.z(), 2).c_str(), heading_target_rad_);
71 }
72 void UpdateSetpointWithGoal(float dt_s, std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
73 std::shared_ptr<Result> result_ptr) final
74 {
75 (void)goal_ptr;
76 (void)dt_s;
77 (void)result_ptr;
78
79 goto_setpoint_ptr_->update(position_target_f_glob_, heading_target_rad_);
80
81 // Remaining distance to target
82 Eigen::Vector3d distance_f_ned =
83 px4_ros2::vectorToGlobalPosition(vehicle_global_position_ptr_->position(), position_target_f_glob_)
84 .cast<double>();
85 tf2::convert(distance_f_ned, feedback_ptr->remaining_distance_f_ned);
86
87 // Estimated remaining time. Use only velocity in direction of target for estimation.
88 feedback_ptr->remaining_time_s =
89 distance_f_ned.norm() /
90 (vehicle_local_position_ptr_->velocityNed().cast<double>().dot(distance_f_ned.normalized()));
91
92 if (IsPositionReached(position_target_f_glob_))
93 {
94 completed(px4_ros2::Result::Success);
95 }
96 }
97};
98
99class GoToTask : public ModeExecutorFactory<GoToActionType, GoToMode>
100{
101public:
102 explicit GoToTask(const rclcpp::NodeOptions& options) : ModeExecutorFactory{ GO_TO_TASK_NAME, options }
103 {
104 }
105};
106
107} // namespace auto_apms_px4
108
109#include "rclcpp_components/register_node_macro.hpp"
110RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::GoToTask)
ModeExecutorFactory(const std::string &name, const rclcpp::NodeOptions &options, const std::string &topic_namespace_prefix="", bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=auto_apms_core::Task< GoToActionType >::DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=auto_apms_core::Task< GoToActionType >::DEFAULT_VALUE_FEEDBACK_INTERVAL)
std::shared_ptr< px4_ros2::OdometryGlobalPosition > vehicle_global_position_ptr_
Definition mode.hpp:99
std::shared_ptr< px4_ros2::OdometryLocalPosition > vehicle_local_position_ptr_
Definition mode.hpp:100
bool IsPositionReached(const Eigen::Vector3d &target_position_f_glob) const
Definition mode.hpp:105
const char GO_TO_TASK_NAME[]
Definition constants.hpp:23
auto_apms_interfaces::action::GoTo GoToActionType
Definition goto.cpp:28