Skip to content

Commit

Permalink
Change std::function<void(void)> to a type alias
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Jun 2, 2022
1 parent c66eaf3 commit f6471a5
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 18 deletions.
22 changes: 11 additions & 11 deletions bondcpp/include/bondcpp/bond.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ namespace bond
class Bond
{
public:
using EventCallback = std::function<void (void)>;
/** \brief Constructs a bond, but does not connect
*
* \param topic The topic used to exchange the bond status messages.
Expand All @@ -70,8 +71,8 @@ class Bond
Bond(
const std::string & topic, const std::string & id,
rclcpp_lifecycle::LifecycleNode::SharedPtr nh,
std::function<void(void)> on_broken = std::function<void(void)>(),
std::function<void(void)> on_formed = std::function<void(void)>());
EventCallback on_broken = EventCallback(),
EventCallback on_formed = EventCallback());

/** \brief Constructs a bond, but does not connect
*
Expand All @@ -85,8 +86,8 @@ class Bond
Bond(
const std::string & topic, const std::string & id,
rclcpp::Node::SharedPtr nh,
std::function<void(void)> on_broken = std::function<void(void)>(),
std::function<void(void)> on_formed = std::function<void(void)>());
EventCallback on_broken = EventCallback(),
EventCallback on_formed = EventCallback());

/** \brief Destructs the object, breaking the bond if it is still formed.
*/
Expand Down Expand Up @@ -120,11 +121,11 @@ class Bond
void start();
/** \brief Sets the formed callback.
*/
void setFormedCallback(std::function<void(void)> on_formed);
void setFormedCallback(EventCallback on_formed);

/** \brief Sets the broken callback
*/
void setBrokenCallback(std::function<void(void)> on_broken);
void setBrokenCallback(EventCallback on_broken);

/** \brief Blocks until the bond is formed for at most 'duration'.
* Assumes the node to be spinning in the background
Expand Down Expand Up @@ -162,7 +163,7 @@ class Bond
void doPublishing();
void publishStatus(bool active);

std::vector<std::function<void(void)>> pending_callbacks_;
std::vector<EventCallback> pending_callbacks_;
void flushPendingCallbacks();

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
Expand All @@ -182,8 +183,9 @@ class Bond
std::string id_;
std::string instance_id_;
std::string sister_instance_id_;
std::function<void(void)> on_broken_;
std::function<void(void)> on_formed_;
EventCallback on_broken_;
EventCallback on_formed_;

bool sisterDiedFirst_;
bool started_;
bool connect_timer_reset_flag_;
Expand All @@ -201,10 +203,8 @@ class Bond
rclcpp::Subscription<bond::msg::Status>::SharedPtr sub_;
rclcpp::Publisher<bond::msg::Status>::SharedPtr pub_;
};

} // namespace bond


// Internal use only
struct BondSM
{
Expand Down
14 changes: 7 additions & 7 deletions bondcpp/src/bond.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ static std::string makeUUID()
Bond::Bond(
const std::string & topic, const std::string & id,
rclcpp_lifecycle::LifecycleNode::SharedPtr nh,
std::function<void(void)> on_broken,
std::function<void(void)> on_formed)
EventCallback on_broken,
EventCallback on_formed)
: bondsm_(new BondSM(this)),
sm_(*bondsm_),
topic_(topic),
Expand Down Expand Up @@ -108,8 +108,8 @@ Bond::Bond(
Bond::Bond(
const std::string & topic, const std::string & id,
rclcpp::Node::SharedPtr nh,
std::function<void(void)> on_broken,
std::function<void(void)> on_formed)
EventCallback on_broken,
EventCallback on_formed)
: bondsm_(new BondSM(this)),
sm_(*bondsm_),
topic_(topic),
Expand Down Expand Up @@ -380,13 +380,13 @@ void Bond::start()
started_ = true;
}

void Bond::setFormedCallback(std::function<void(void)> on_formed)
void Bond::setFormedCallback(EventCallback on_formed)
{
std::unique_lock<std::mutex> lock(mutex_);
on_formed_ = on_formed;
}

void Bond::setBrokenCallback(std::function<void(void)> on_broken)
void Bond::setBrokenCallback(EventCallback on_broken)
{
std::unique_lock<std::mutex> lock(mutex_);
on_broken_ = on_broken;
Expand Down Expand Up @@ -545,7 +545,7 @@ void Bond::publishStatus(bool active)

void Bond::flushPendingCallbacks()
{
std::vector<std::function<void(void)>> callbacks;
std::vector<EventCallback> callbacks;
{
std::unique_lock<std::mutex> lock(mutex_);
callbacks = pending_callbacks_;
Expand Down

0 comments on commit f6471a5

Please sign in to comment.