Program Listing for File aerial_platform.hpp
↰ Return to documentation for file (include/as2_core/aerial_platform.hpp
)
// Copyright 2023 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.
/*!*******************************************************************************************
* \file aerial_platform.hpp
* \brief Aerostack2 Aerial Platformm class header file.
* \authors Miguel Fernández Cortizas
* Pedro Arias Pérez
* David Pérez Saura
* Rafael Pérez Seguí
********************************************************************************/
#ifndef AS2_CORE__AERIAL_PLATFORM_HPP_
#define AS2_CORE__AERIAL_PLATFORM_HPP_
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include <vector>
#include "as2_core/names/services.hpp"
#include "as2_core/names/topics.hpp"
#include "as2_core/platform_state_machine.hpp"
#include "as2_msgs/msg/alert_event.hpp"
#include "as2_msgs/msg/control_mode.hpp"
#include "as2_msgs/msg/platform_info.hpp"
#include "as2_msgs/msg/platform_status.hpp"
#include "as2_msgs/msg/thrust.hpp"
#include "as2_msgs/msg/trajectory_point.hpp"
#include "as2_msgs/srv/list_control_modes.hpp"
#include "as2_msgs/srv/set_control_mode.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "as2_core/node.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "utils/control_mode_utils.hpp"
#include "utils/yaml_utils.hpp"
namespace as2
{
class AerialPlatform : public as2::Node
{
private:
void initialize();
bool sending_commands_ = false;
rclcpp::TimerBase::SharedPtr platform_cmd_timer_;
rclcpp::TimerBase::SharedPtr platform_info_timer_;
as2::PlatformStateMachine state_machine_;
std::vector<uint8_t> available_control_modes_;
protected:
float cmd_freq_;
float info_freq_;
as2_msgs::msg::TrajectoryPoint command_trajectory_msg_;
geometry_msgs::msg::PoseStamped command_pose_msg_;
geometry_msgs::msg::TwistStamped command_twist_msg_;
as2_msgs::msg::Thrust command_thrust_msg_;
as2_msgs::msg::PlatformInfo platform_info_msg_;
public:
explicit AerialPlatform(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
AerialPlatform(
const std::string & ns, const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~AerialPlatform() {}
virtual void configureSensors() = 0;
virtual bool ownSendCommand() = 0;
virtual bool ownSetArmingState(bool state) = 0;
virtual bool ownSetOffboardControl(bool offboard) = 0;
virtual bool ownSetPlatformControlMode(const as2_msgs::msg::ControlMode & msg) = 0;
virtual bool ownTakeoff() {return false;}
virtual bool ownLand() {return false;}
virtual void ownKillSwitch() = 0;
virtual void ownStopPlatform() = 0;
protected:
bool setArmingState(bool state);
bool setOffboardControl(bool offboard);
bool setPlatformControlMode(const as2_msgs::msg::ControlMode & msg);
bool takeoff();
bool land();
void alertEvent(const as2_msgs::msg::AlertEvent & msg);
virtual void sendCommand();
private:
void loadControlModes(const std::string & filename);
// Getters
public:
bool handleStateMachineEvent(const as2_msgs::msg::PlatformStateMachineEvent & event)
{
return state_machine_.processEvent(event);
}
bool handleStateMachineEvent(const int8_t & event) {return state_machine_.processEvent(event);}
inline bool getArmingState() const {return platform_info_msg_.armed;}
inline bool getConnectedStatus() const {return platform_info_msg_.connected;}
inline bool getOffboardMode() const {return platform_info_msg_.offboard;}
inline as2_msgs::msg::ControlMode & getControlMode()
{
return platform_info_msg_.current_control_mode;
}
inline bool isControlModeSettled() const
{
return platform_info_msg_.current_control_mode.control_mode !=
platform_info_msg_.current_control_mode.UNSET;
}
protected:
bool has_new_references_ = false;
// ROS publishers & subscribers
private:
rclcpp::Publisher<as2_msgs::msg::PlatformInfo>::SharedPtr platform_info_pub_;
rclcpp::Subscription<as2_msgs::msg::TrajectoryPoint>::SharedPtr trajectory_command_sub_;
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr pose_command_sub_;
rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr twist_command_sub_;
rclcpp::Subscription<as2_msgs::msg::Thrust>::SharedPtr thrust_command_sub_;
rclcpp::Subscription<as2_msgs::msg::AlertEvent>::SharedPtr alert_event_sub_;
void publishPlatformInfo()
{
platform_info_msg_.header.stamp = this->now();
platform_info_msg_.status = state_machine_.getState();
platform_info_pub_->publish(platform_info_msg_);
}
void alertEventCallback(const as2_msgs::msg::AlertEvent::SharedPtr msg);
// ROS Services & srv callbacks
private:
rclcpp::Service<as2_msgs::srv::SetControlMode>::SharedPtr set_platform_mode_srv_;
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_arming_state_srv_;
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_offboard_mode_srv_;
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr platform_takeoff_srv_;
rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr platform_land_srv_;
rclcpp::Service<as2_msgs::srv::ListControlModes>::SharedPtr list_control_modes_srv_;
void setPlatformControlModeSrvCall(
const std::shared_ptr<as2_msgs::srv::SetControlMode::Request> request,
std::shared_ptr<as2_msgs::srv::SetControlMode::Response> response);
void setArmingStateSrvCall(
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response);
void setOffboardModeSrvCall(
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response);
void platformTakeoffSrvCall(
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response);
void platformLandSrvCall(
const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
std::shared_ptr<std_srvs::srv::SetBool::Response> response);
void listControlModesSrvCall(
const std::shared_ptr<as2_msgs::srv::ListControlModes::Request> request,
std::shared_ptr<as2_msgs::srv::ListControlModes::Response> response);
}; // class AerialPlatform
} // namespace as2
#endif // AS2_CORE__AERIAL_PLATFORM_HPP_