Class Node

Inheritance Relationships

Base Type

  • public AS2_NODE_FATHER_TYPE

Derived Types

Class Documentation

class Node : public AS2_NODE_FATHER_TYPE

Basic Aerostack2 Node, it heritages all the functionality of an rclcpp::Node.

Subclassed by as2::AerialPlatform, as2::BasicBehavior< MessageT >

Public Functions

inline Node(const std::string &name, const std::string &ns, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new Node object.

Parameters:

nameNode name

inline explicit Node(const std::string &name, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
inline void configure()
inline void activate()
inline void deactivate()
inline void cleanup()
inline void shutdown()
inline void error()
std::string generate_local_name(const std::string &name)

transform an string into local topic name inside drone namespace and node namespace

Parameters:

name – source string

Returns:

std::string result name

std::string generate_global_name(const std::string &name)

transform an string into global topic name inside drone namespace

Parameters:

name – source string

Returns:

std::string result name

template<typename DurationRepT, typename DurationT, typename CallbackT>
inline rclcpp::TimerBase::SharedPtr create_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr)

create a timer with the node clock

Returns:

rclcpp::TimerBase::SharedPtr rclcpp timer using node clock

inline bool sleep()

sleeps the node to ensure node_frecuency desired

Returns:

true the node is sleeping

Returns:

false the node is not sleeping, this means that desired frequency is not reached

inline double get_loop_frequency()

Get the loop frequency object.

Returns:

double frequency in Hz

inline bool preset_loop_frequency(double frequency)

Protected Types

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

Callback for the activate state.

Param state:

Return:

CallbackReturn

Protected Functions

inline virtual CallbackReturn on_activate(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())
inline virtual CallbackReturn on_deactivate(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())

Callback for the deactivate state.

Parameters:

state

Returns:

CallbackReturn

inline virtual CallbackReturn on_configure(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())

Callback for the configure state.

Parameters:

state

Returns:

CallbackReturn

inline virtual CallbackReturn on_cleanup(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())

Callback for the cleanup state.

Parameters:

state

Returns:

CallbackReturn

inline virtual CallbackReturn on_shutdown(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())

Callback for the shutdown state.

Parameters:

state

Returns:

CallbackReturn

inline virtual CallbackReturn on_error(const rclcpp_lifecycle::State& = rclcpp_lifecycle::State())

Callback for the error state.

Parameters:

state

Returns:

CallbackReturn