Program Listing for File takeoff_plugin_position.cpp
↰ Return to documentation for file (/tmp/ws/src/aerostack2/as2_behaviors/as2_behaviors_motion/takeoff_behavior/plugins/takeoff_plugin_position.cpp
)
// Copyright 2024 Universidad Politécnica de Madrid
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Universidad Politécnica de Madrid nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#include <geometry_msgs/msg/point.hpp>
#include "as2_behavior/behavior_server.hpp"
#include "as2_core/utils/frame_utils.hpp"
#include "as2_motion_reference_handlers/position_motion.hpp"
#include "takeoff_behavior/takeoff_base.hpp"
namespace takeoff_plugin_position
{
class Plugin : public takeoff_base::TakeoffBase
{
private:
std::shared_ptr<as2::motionReferenceHandlers::PositionMotion> position_motion_handler_ = nullptr;
public:
void ownInit()
{
position_motion_handler_ =
std::make_shared<as2::motionReferenceHandlers::PositionMotion>(node_ptr_);
}
bool own_activate(as2_msgs::action::Takeoff::Goal & _goal) override
{
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff accepted");
takeoff_position_.x = actual_pose_.pose.position.x;
takeoff_position_.y = actual_pose_.pose.position.y;
takeoff_position_.z = actual_pose_.pose.position.z + _goal.takeoff_height;
takeoff_angle_ = as2::frame::getYawFromQuaternion(actual_pose_.pose.orientation);
RCLCPP_INFO(
node_ptr_->get_logger(), "Takeoff to position: %f, %f, %f", takeoff_position_.x,
takeoff_position_.y, takeoff_position_.z);
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff with angle: %f", takeoff_angle_);
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff with speed: %f", _goal.takeoff_speed);
return true;
}
bool own_modify(as2_msgs::action::Takeoff::Goal & _goal) override
{
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff accepted");
takeoff_position_.x = actual_pose_.pose.position.x;
takeoff_position_.y = actual_pose_.pose.position.y;
takeoff_position_.z = actual_pose_.pose.position.z + _goal.takeoff_height;
takeoff_angle_ = as2::frame::getYawFromQuaternion(actual_pose_.pose.orientation);
RCLCPP_INFO(
node_ptr_->get_logger(), "Takeoff to position: %f, %f, %f", takeoff_position_.x,
takeoff_position_.y, takeoff_position_.z);
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff with angle: %f", takeoff_angle_);
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff with speed: %f", _goal.takeoff_speed);
return true;
}
bool own_deactivate(const std::shared_ptr<std::string> & message) override
{
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff canceled, set to hover");
sendHover();
return true;
}
void own_execution_end(const as2_behavior::ExecutionStatus & state) override
{
RCLCPP_INFO(node_ptr_->get_logger(), "Takeoff end");
if (state == as2_behavior::ExecutionStatus::SUCCESS) {
// Leave the drone in the last position
if (position_motion_handler_->sendPositionCommandWithYawAngle(
"earth", takeoff_position_.x, takeoff_position_.y, takeoff_position_.z,
takeoff_angle_, "earth", goal_.takeoff_speed, goal_.takeoff_speed,
goal_.takeoff_speed))
{
return;
}
}
sendHover();
return;
}
as2_behavior::ExecutionStatus own_run() override
{
if (checkGoalCondition()) {
result_.takeoff_success = true;
RCLCPP_INFO(node_ptr_->get_logger(), "Goal succeeded");
return as2_behavior::ExecutionStatus::SUCCESS;
}
if (!position_motion_handler_->sendPositionCommandWithYawAngle(
"earth", takeoff_position_.x, takeoff_position_.y, takeoff_position_.z, takeoff_angle_,
"earth", goal_.takeoff_speed, goal_.takeoff_speed, goal_.takeoff_speed))
{
RCLCPP_ERROR(node_ptr_->get_logger(), "Take Off PLUGIN: Error sending speed command");
result_.takeoff_success = false;
return as2_behavior::ExecutionStatus::FAILURE;
}
return as2_behavior::ExecutionStatus::RUNNING;
}
private:
geometry_msgs::msg::Point takeoff_position_;
double takeoff_angle_;
bool checkGoalCondition()
{
if (localization_flag_) {
if (fabs(goal_.takeoff_height - feedback_.actual_takeoff_height) <
params_.takeoff_threshold)
{
return true;
}
}
return false;
}
}; // Plugin class
} // namespace takeoff_plugin_position
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(takeoff_plugin_position::Plugin, takeoff_base::TakeoffBase)