15#include "px4_ros2/control/setpoint_types/goto.hpp"
19#include "auto_apms_interfaces/action/go_to.hpp"
22#include "px4_ros2/utils/geodesic.hpp"
23#include "tf2_eigen/tf2_eigen.hpp"
32 std::shared_ptr<px4_ros2::GotoGlobalSetpointType> goto_setpoint_ptr_;
33 Eigen::Vector3d position_target_f_glob_;
34 float heading_target_rad_;
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)
41 goto_setpoint_ptr_ = std::make_shared<px4_ros2::GotoGlobalSetpointType>(*
this);
45 void OnActivateWithGoal(std::shared_ptr<const Goal> goal_ptr)
final
47 position_target_f_glob_ = Eigen::Vector3d(goal_ptr->lat, goal_ptr->lon, goal_ptr->alt);
50 if (goal_ptr->head_towards_destination)
58 heading_target_rad_ = goal_ptr->heading_clockwise_from_north_rad;
61 auto double_to_string = [](
double num,
int decimals) {
62 std::stringstream stream;
63 stream << std::fixed << std::setprecision(decimals) << num;
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_);
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
79 goto_setpoint_ptr_->update(position_target_f_glob_, heading_target_rad_);
82 Eigen::Vector3d distance_f_ned =
85 tf2::convert(distance_f_ned, feedback_ptr->remaining_distance_f_ned);
88 feedback_ptr->remaining_time_s =
89 distance_f_ned.norm() /
94 completed(px4_ros2::Result::Success);
99class GoToTask :
public ModeExecutorFactory<GoToActionType, GoToMode>
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_
std::shared_ptr< px4_ros2::OdometryLocalPosition > vehicle_local_position_ptr_
bool IsPositionReached(const Eigen::Vector3d &target_position_f_glob) const
const char GO_TO_TASK_NAME[]
auto_apms_interfaces::action::GoTo GoToActionType