Skip to content

Observer #46

@tylerjw

Description

@tylerjw

Use cases

  1. update latest state then run some behavior
    • behavior can update other state (chained update?)
  2. calculate output from input and publish output
stateDiagram-v2

Callback --> UpdateLatestState

Timer --> ReadLatestState
ReadLatestState --> transform
transform --> publish
Loading

Read a latest state, need to know if it has been updated since you read.

/// in header
rsl::Observer<std_msgs::msg::Int8> status_;

/// in initalizer_list
Foo::Foo() :
	status_{
	    node_,                            // rclcpp::Node
	    "topic name",                     // std::string
	    std_msgs::msg::Int8{ .val = 0; }, // initial value
	    QoS,                              // Optional QoS param
	}
{}

/// in timer or thread loop
auto latest_status = status_.get();
template<typename MessageT>
class Observer
{
  std::atomic<MessageT> msg_;
  std::shared_ptr<rclcpp::Subscription<MessageT>> subscription_;

public:
  auto get() { return msg_.load(); }
  operator MessageT() { return get(); }

  Observer(std::shared_ptr<rclcpp::Node> node,
    std::string const& topic,
    MessageT initial_value,
    rclcpp::QoS qos = rclcpp::DefaultQoS());
};

template<typename MessageT>
Observer::Observer(
    std::shared_ptr<const rclcpp::Node> const& node,
    std::string const& topic,
    MessageT const& initial_value,
    rclcpp::QoS qos = rclcpp::SystemDefaultsQoS())
: msg_{initial_value}
, subscription_{
  node->create_subscription<MessageT>(
       topic, [this](auto msg) { msg_ = msg; }, qos)
}
{
   assert(subscription_);
}

TODO:

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions