Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Observer #46

Open
Tracked by #37
tylerjw opened this issue Oct 24, 2022 · 1 comment
Open
Tracked by #37

Observer #46

tylerjw opened this issue Oct 24, 2022 · 1 comment

Comments

@tylerjw
Copy link
Collaborator

tylerjw commented Oct 24, 2022

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:

@tylerjw tylerjw mentioned this issue Oct 24, 2022
5 tasks
@ChrisThrasher
Copy link
Collaborator

See https://github.com/PickNikRobotics/RSL/commits/observer. CI is failing due to Asan violation in rclcpp code.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants