Skip to content

Commit

Permalink
(dev) composition over inheritance
Browse files Browse the repository at this point in the history
  • Loading branch information
Karsten1987 committed Nov 10, 2016
1 parent 1a592d6 commit e86473e
Show file tree
Hide file tree
Showing 6 changed files with 85 additions and 31 deletions.
6 changes: 4 additions & 2 deletions rclcpp_lifecycle/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,13 @@ macro(targets)
"rclcpp${target_suffix}"
"std_msgs")

install(TARGETS rclcpp_lifecycle${target_suffix} lifecycle_talker${target_suffix}
install(TARGETS
rclcpp_lifecycle${target_suffix}
lifecycle_talker${target_suffix}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
)
endmacro()

call_for_each_rmw_implementation(targets GENERATE_DEFAULT)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,15 +63,19 @@ class LIFECYCLE_EXPORT LifecycleManager : public LifecycleManagerInterface
{
public:
using NodeInterfacePtr = std::shared_ptr<node::lifecycle::LifecycleNodeInterface>;
using NodePtr = std::shared_ptr<node::lifecycle::LifecycleNode>;

LifecycleManager();
~LifecycleManager();

void
add_node_interface(const NodeInterfacePtr & node_interface);
add_node_interface(const NodePtr & node);

void
add_node_interface(const NodeInterfacePtr & node_interface,
add_node_interface(const std::string & node_name, const NodeInterfacePtr & node_interface);

void
add_node_interface(const std::string & node_name, const NodeInterfacePtr & node_interface,
rcl_state_machine_t custom_state_machine);

template<typename T>
Expand Down
52 changes: 39 additions & 13 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,35 +60,49 @@ class LifecycleNodeInterface
virtual bool on_activate() {return true; }
virtual bool on_deactivate() {return true; }
virtual bool on_error() {return true; }
// hardcoded mock
// as we don't have a node base class yet
virtual std::string get_name()
{
static auto counter = 0;
std::string tmp_name = "my_node" + std::to_string(++counter);
return tmp_name;
}
};

/**
* @brief LifecycleNode as child class of rclcpp Node
* has lifecycle nodeinterface for configuring this node.
*/
class LifecycleNode : public rclcpp::node::Node, public lifecycle::LifecycleNodeInterface
class LifecycleNode : public lifecycle::LifecycleNodeInterface
{
public:
using LifecyclePublisherWeakPtr =
std::weak_ptr<rclcpp::publisher::lifecycle_interface::PublisherInterface>;

LIFECYCLE_EXPORT
explicit LifecycleNode(const std::string & node_name, bool use_intra_process_comms = false)
: Node(node_name, use_intra_process_comms)
{
}
: base_interface_(std::make_shared<rclcpp::node::Node>(node_name, use_intra_process_comms)),
communication_interface_(base_interface_) // MOCK as base/comms interface not done yet
{}

LIFECYCLE_EXPORT
~LifecycleNode() {}

// MOCK typedefs as node refactor not done yet
using BaseInterface = rclcpp::node::Node;
std::shared_ptr<BaseInterface>
get_base_interface()
{
return base_interface_;
}

// MOCK typedefs as node refactor not done yet
using CommunicationInterface = rclcpp::node::Node;
std::shared_ptr<CommunicationInterface>
get_communication_interface()
{
return communication_interface_;
}

std::string
get_name()
{
return base_interface_->get_name();
}

/**
* @brief same API for creating publisher as regular Node
*/
Expand All @@ -100,7 +114,7 @@ class LifecycleNode : public rclcpp::node::Node, public lifecycle::LifecycleNode
std::shared_ptr<Alloc> allocator = nullptr)
{
// create regular publisher in rclcpp::Node
auto pub = rclcpp::node::Node::create_publisher<MessageT, Alloc,
auto pub = communication_interface_->create_publisher<MessageT, Alloc,
rclcpp::publisher::LifecyclePublisher<MessageT, Alloc>>(
topic_name, qos_profile, allocator);

Expand All @@ -109,6 +123,16 @@ class LifecycleNode : public rclcpp::node::Node, public lifecycle::LifecycleNode
return pub;
}

template<typename CallbackType>
typename rclcpp::timer::WallTimer<CallbackType>::SharedPtr
create_wall_timer(
std::chrono::nanoseconds period,
CallbackType callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
{
return communication_interface_->create_wall_timer(period, callback, group);
}

LIFECYCLE_EXPORT
virtual bool
disable_communication()
Expand Down Expand Up @@ -138,6 +162,8 @@ class LifecycleNode : public rclcpp::node::Node, public lifecycle::LifecycleNode
}

private:
std::shared_ptr<BaseInterface> base_interface_;
std::shared_ptr<CommunicationInterface> communication_interface_;
// Placeholder for all pub/sub/srv/clients
std::vector<LifecyclePublisherWeakPtr> weak_pubs_;
};
Expand Down
16 changes: 12 additions & 4 deletions rclcpp_lifecycle/src/rclcpp_lifecycle/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,16 +30,24 @@ LifecycleManager::LifecycleManager()
LifecycleManager::~LifecycleManager() = default;

void
LifecycleManager::add_node_interface(const NodeInterfacePtr & node_interface)
LifecycleManager::add_node_interface(const NodePtr & node)
{
impl_->add_node_interface(node_interface);
add_node_interface(node->get_base_interface()->get_name(), node);
}

void
LifecycleManager::add_node_interface(const NodeInterfacePtr & node_interface,
LifecycleManager::add_node_interface(const std::string & node_name,
const NodeInterfacePtr & node_interface)
{
impl_->add_node_interface(node_name, node_interface);
}

void
LifecycleManager::add_node_interface(const std::string & node_name,
const NodeInterfacePtr & node_interface,
rcl_state_machine_t custom_state_machine)
{
impl_->add_node_interface(node_interface, custom_state_machine);
impl_->add_node_interface(node_name, node_interface, custom_state_machine);
}

bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,14 +50,14 @@ class LIFECYCLE_EXPORT LifecycleManager::LifecycleManagerImpl
~LifecycleManagerImpl() = default;

void
add_node_interface(const NodeInterfacePtr & node_interface)
add_node_interface(const std::string & node_name, const NodeInterfacePtr & node_interface)
{
rcl_state_machine_t state_machine = rcl_get_default_state_machine();
add_node_interface(node_interface, state_machine);
add_node_interface(node_name, node_interface, state_machine);
}

void
add_node_interface(const NodeInterfacePtr & node_interface,
add_node_interface(const std::string & node_name, const NodeInterfacePtr & node_interface,
rcl_state_machine_t custom_state_machine)
{
NodeStateMachine node_state_machine;
Expand Down Expand Up @@ -86,8 +86,7 @@ class LIFECYCLE_EXPORT LifecycleManager::LifecycleManagerImpl
node_state_machine.cb_map[LifecycleTransitionsT::DEACTIVATING] = cb_deactivating;
node_state_machine.cb_map[LifecycleTransitionsT::ERRORPROCESSING] = cb_error;

// TODO(karsten1987): clarify what do if node already exists
auto node_name = node_interface->get_name();
// TODO(karsten1987): clarify what do if node already exists;
node_handle_map_[node_name] = node_state_machine;
}

Expand Down
25 changes: 20 additions & 5 deletions rclcpp_lifecycle/src/rclcpp_lifecycle/lifecycle_talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@

#include "std_msgs/msg/string.hpp"

#define STRICTLY_DRY 0

class MyLifecycleNode : public rclcpp::node::lifecycle::LifecycleNode
{
public:
Expand All @@ -33,9 +35,16 @@ class MyLifecycleNode : public rclcpp::node::lifecycle::LifecycleNode
{
msg_ = std::make_shared<std_msgs::msg::String>();

#if STRICTLY_DRY
// Version 1
pub_ = this->get_communication_interface()->create_publisher<std_msgs::msg::String>("chatter");
timer_ = this->get_communication_interface()->create_wall_timer(
1_s, std::bind(&MyLifecycleNode::publish, this));
#else
// Version 2
pub_ = this->create_publisher<std_msgs::msg::String>("chatter");

timer_ = this->create_wall_timer(1_s, std::bind(&MyLifecycleNode::publish, this));
#endif
}

void publish()
Expand Down Expand Up @@ -81,10 +90,16 @@ int main(int argc, char * argv[])

std::shared_ptr<MyLifecycleNode> lc_node = std::make_shared<MyLifecycleNode>("lc_talker");

#if STRICTLY_DRY
auto node_name = lc_node->get_base_interface()->get_name();
#else
auto node_name = lc_node->get_name();
#endif

rclcpp::lifecycle::LifecycleManager lm;
lm.add_node_interface(lc_node);

exe.add_node(lc_node);
exe.add_node(lc_node->get_communication_interface());

auto time_out_lambda = []() -> int {
std::this_thread::sleep_for(std::chrono::seconds(10));
Expand All @@ -93,15 +108,15 @@ int main(int argc, char * argv[])

// configure
// dummy mockup for now!
lm.configure("my_node1");
lm.configure(node_name);
std::shared_future<int> time_out = std::async(std::launch::async, time_out_lambda);
exe.spin_until_future_complete(time_out);

lm.activate("my_node1");
lm.activate(node_name);
time_out = std::async(std::launch::async, time_out_lambda);
exe.spin_until_future_complete(time_out);

lm.deactivate("my_node1");
lm.deactivate(node_name);
time_out = std::async(std::launch::async, time_out_lambda);
exe.spin_until_future_complete(time_out);

Expand Down

0 comments on commit e86473e

Please sign in to comment.