Class AerialPlatform

Inheritance Relationships

Base Type

Class Documentation

class AerialPlatform : public as2::Node

Base class for all Aerial platforms. It provides the basic functionality for the platform. It is responsible for handling the platform state machine and the platform status. It also handles the command subscriptions and the basic platform services.

Public Functions

explicit AerialPlatform(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new Aerial Platform object, with default parameters.

AerialPlatform(const std::string &ns, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new Aerial Platform object, with default parameters.

inline ~AerialPlatform()
virtual void configureSensors() = 0

Configures the platform sensors.

virtual bool ownSendCommand() = 0

Handles how a command must be sended in the concrete platform.

Returns:

true command is sended successfully.

Returns:

false command is not sended.

virtual bool ownSetArmingState(bool state) = 0

Handles how arming state has to be settled in the concrete platform.

Parameters:

state – true for arming the platform, false to disarm.

Returns:

true Arming state is settled successfully.

Returns:

false Arming state is not settled.

virtual bool ownSetOffboardControl(bool offboard) = 0

Handles how offboard mode has to be settled in the concrete platform.

Parameters:

offboard – true if offboard mode is enabled.

Returns:

true Offboard mode is settled successfully.

Returns:

false Offboard mode is not settled.

virtual bool ownSetPlatformControlMode(const as2_msgs::msg::ControlMode &msg) = 0

Handles how the control mode has to be settled in the concrete platform.

Parameters:

control_mode – as2_msgs::msg::PlatformControlMode with the new control mode.

Returns:

true Control mode is settled successfully.

Returns:

false Control mode is not settled.

inline virtual bool ownTakeoff()

Handles the platform takeoff command.

Returns:

true Takeoff command is sended successfully.

Returns:

false Takeoff command is not sended.

inline virtual bool ownLand()

Handles the platform landing command.

Returns:

true Landing command is sended successfully.

Returns:

false Landing command is not sended.

virtual void ownKillSwitch() = 0

Handles the platform emergency kill switch command. This means stop the motors inmediately, this cannot be reversed. USE WITH CAUTION.

virtual void ownStopPlatform() = 0

Handles the platform emergency stop command. STOP means to hover as best as possible. This hover is different from the hover in the platform control mode. And when it is activated the platform will stop hearing commands from AS2. USE WITH CAUTION.

inline bool handleStateMachineEvent(const as2_msgs::msg::PlatformStateMachineEvent &event)

Set the State Machine Event object.

Parameters:

event – Event to

Returns:

true

Returns:

false

inline bool handleStateMachineEvent(const int8_t &event)
inline bool getArmingState() const

Get whether the platform is armed or not.

Returns:

true Armed

Returns:

false Disarmed

inline bool getConnectedStatus() const

Get wheter the connection is established or not.

Returns:

true Connection active

Returns:

false Connection not active

inline bool getOffboardMode() const

Get whether offboard mode is active or not.

Returns:

true Offboard mode enabled

Returns:

false Offboard mode disabled

inline as2_msgs::msg::ControlMode &getControlMode()

Get current platform control mode.

Returns:

as2_msgs::msg::PlatformControlMode current platform control mode

inline bool isControlModeSettled() const

Get whether a control mode is active or not.

Returns:

true Control mode set and valid

Returns:

false Control mode unset

Protected Functions

bool setArmingState(bool state)

Set the arm state of the platform.

Parameters:

state – True to arm the platform, false to disarm it.

Returns:

true Armimg state setted successfully.

Returns:

false Armimg state not setted successfully.

bool setOffboardControl(bool offboard)

Set the offboard control mode.

Parameters:

offboard – True if the offboard control mode is enabled.

Returns:

true if the offboard control mode is setted properly

Returns:

false if the offboard control mode could not be setted.

bool setPlatformControlMode(const as2_msgs::msg::ControlMode &msg)

Set the control mode of the platform.

Parameters:

msg – as2_msgs::msg::ControlMode message with the new control mode desired.

Returns:

true If the control mode is set properly.

Returns:

false If the control mode could not be set properly.

bool takeoff()

Handles the platform takeoff command.

Returns:

true Takeoff command is sended successfully.

Returns:

false Takeoff command is not sended.

bool land()

Handles the platform landing command.

Returns:

true Landing command is sended successfully.

Returns:

false Landing command is not sended.

void alertEvent(const as2_msgs::msg::AlertEvent &msg)

Handles the platform emergency event.

Parameters:

msg – as2_msgs::msg::AlertEvent message with the emergency event.

virtual void sendCommand()

Send command to the platform.

Protected Attributes

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_
bool has_new_references_ = false