Skip to content

Commit

Permalink
reduce ros dependencies
Browse files Browse the repository at this point in the history
  • Loading branch information
sarthou committed Jun 24, 2024
1 parent ad3412e commit 7a249ec
Show file tree
Hide file tree
Showing 13 changed files with 228 additions and 266 deletions.
9 changes: 9 additions & 0 deletions include/mementar/API/mementar/ActionsPublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,20 @@ namespace mementar {
void insertEnd(const std::string& name, time_t end_stamp = time(nullptr));
void insertEnd(const std::string& name, compat::mem_ros::Time end_stamp = compat::mem_ros::Node::get().currentTime());

/// @brief Register a callback function to get notifications from the feeder.
/// @param callback is the callback function taking a string.
void registerFeederNotificationCallback(const std::function<void(const std::string&)>& callback) { feeder_notification_callback_ = callback; }

private:
std::function<void(const std::string&)> feeder_notification_callback_;

compat::mem_ros::Publisher<compat::MementarAction> pub_;
compat::mem_ros::Subscriber<std_msgs_compat::String> feeder_notif_sub_;

void publish(const std::string& name, time_t start_stamp, time_t end_stamp);
void publish(const std::string& name, compat::mem_ros::Time start_stamp, compat::mem_ros::Time end_stamp);

void feederNotificationCallback(const compat::mem_ros::MessageWrapper<std_msgs_compat::String>& msg);
};

} // namespace mementar
Expand Down
5 changes: 1 addition & 4 deletions include/mementar/API/mementar/ActionsSubscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,7 @@ namespace mementar {
{
public:
ActionsSubscriber(const std::function<void(const std::string&)>& callback,
const std::string& name = "",
bool spin_thread = true);
ActionsSubscriber(const std::function<void(const std::string&)>& callback,
bool spin_thread);
const std::string& name = "");

bool subscribeToStart(const std::string& name, size_t count = -1);
bool subscribeToEnd(const std::string& name, size_t count = -1);
Expand Down
15 changes: 13 additions & 2 deletions include/mementar/API/mementar/OccasionsPublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,23 @@ namespace mementar {
public:
OccasionsPublisher(const std::string& name = "");

void insert(const Fact& fact, time_t stamp = time(nullptr));
void insert(const Fact& fact, mementar::compat::mem_ros::Time stamp = compat::mem_ros::Node::get().currentTime());
void insert(const Fact& fact, time_t end_stamp);

/// @brief Register a callback function to get notifications from the feeder.
/// @param callback is the callback function taking a string.
void registerFeederNotificationCallback(const std::function<void(const std::string&)>& callback) { feeder_notification_callback_ = callback; }

private:
std::function<void(const std::string&)> feeder_notification_callback_;

compat::mem_ros::Publisher<compat::StampedString> pub_;
compat::mem_ros::Subscriber<std_msgs_compat::String> feeder_notif_sub_;

void publish(const std::string& str, mementar::compat::mem_ros::Time stamp = compat::mem_ros::Node::get().currentTime());
void publish(const std::string& str, time_t end_stamp);

void publish(const std::string& str, time_t stamp = time(nullptr));
void feederNotificationCallback(const compat::mem_ros::MessageWrapper<std_msgs_compat::String>& msg);
};

} // namespace mementar
Expand Down
3 changes: 1 addition & 2 deletions include/mementar/API/mementar/OccasionsSubscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,7 @@ namespace mementar {
class OccasionsSubscriber
{
public:
OccasionsSubscriber(const std::function<void(const Fact&)>& callback, const std::string& name = "", bool spin_thread = true);
OccasionsSubscriber(const std::function<void(const Fact&)>& callback, bool spin_thread);
OccasionsSubscriber(const std::function<void(const Fact&)>& callback, const std::string& name = "");
~OccasionsSubscriber();

bool subscribe(const Fact& pattern, size_t count = -1);
Expand Down
1 change: 0 additions & 1 deletion include/mementar/RosInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ namespace mementar {
void ontoStampedKnowledgeCallback(const compat::mem_ros::MessageWrapper<ontologenius::compat::OntologeniusStampedString>& msg);
void ontoExplanationKnowledgeCallback(const compat::mem_ros::MessageWrapper<ontologenius::compat::OntologeniusExplanation>& msg);

// todo: do not return bool
bool managerInstanceHandle(compat::mem_ros::ServiceWrapper<compat::MementarService::Request>& req,
compat::mem_ros::ServiceWrapper<compat::MementarService::Response>& res);

Expand Down
17 changes: 0 additions & 17 deletions include/mementar/compat/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,6 @@ namespace mementar::compat {
template<typename T, typename Response_ = typename T::Response>
inline auto makeResponse() { return Response_(); }

// todo: RequestType, ResponseType

#elif MEME_ROS_VERSION == 2
using namespace ::mementar::msg;
using namespace ::mementar::srv;
Expand Down Expand Up @@ -253,8 +251,6 @@ namespace mementar::compat {
{
auto& node = Node::get();

printf("[Publisher '%s'] Create\n", topic_name.c_str());

#if MEME_ROS_VERSION == 1
handle_ = node.handle_.advertise<T>(topic_name, queue_size);
#elif MEME_ROS_VERSION == 2
Expand All @@ -265,8 +261,6 @@ namespace mementar::compat {

void publish(const T& message)
{
printf("[Publisher '%s'] Create\n", name_.c_str());

#if MEME_ROS_VERSION == 1
handle_.publish(message);
#elif MEME_ROS_VERSION == 2
Expand Down Expand Up @@ -302,8 +296,6 @@ namespace mementar::compat {
{
auto& node = Node::get();

printf("[Subscriber '%s'] Create\n", topic_name.c_str());

#if MEME_ROS_VERSION == 1
handle_ = node.handle_.subscribe(topic_name, queue_size, callback, ptr);
#elif MEME_ROS_VERSION == 2
Expand Down Expand Up @@ -331,8 +323,6 @@ namespace mementar::compat {
{
auto& node = Node::get();

printf("[Service '%s'] Create\n", service_name.c_str());

#if MEME_ROS_VERSION == 1
handle_ = node.handle_.advertiseService(service_name, callback);
#elif MEME_ROS_VERSION == 2
Expand All @@ -352,8 +342,6 @@ namespace mementar::compat {
{
auto& node = Node::get();

printf("[Service '%s'] Create\n", service_name.c_str());

#if MEME_ROS_VERSION == 1
handle_ = node.handle_.advertiseService(service_name, callback, ptr);
#elif MEME_ROS_VERSION == 2
Expand Down Expand Up @@ -388,8 +376,6 @@ namespace mementar::compat {
{
auto& node = Node::get();

printf("[Client '%s'] Create\n", service_name.c_str());

#if MEME_ROS_VERSION == 1
handle_ = node.handle_.serviceClient<T>(service_name, true);
#elif MEME_ROS_VERSION == 2
Expand All @@ -399,8 +385,6 @@ namespace mementar::compat {

RosStatus_e call(const mementar::compat::RequestType<T>& req, mementar::compat::ResponseType<T>& res)
{
printf("[Client '%s'] Call\n", name_.c_str());

using namespace std::chrono_literals;
auto status = RosStatus_e::ros_status_failure;

Expand Down Expand Up @@ -442,7 +426,6 @@ namespace mementar::compat {

bool wait(double timeout)
{
printf("[Client '%s'] Wait\n", name_.c_str());
#if MEME_ROS_VERSION == 1
return handle_.waitForExistence(ros::Duration(timeout));
#elif MEME_ROS_VERSION == 2
Expand Down
17 changes: 9 additions & 8 deletions include/mementar/graphical/mementarGUI/mementargui.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@

#include "include/mementar/graphical/mementarGUI/CallBackTimer.h"
#include "include/mementar/graphical/mementarGUI/QCheckBoxExtended.h"
#include "mementar/API/mementar/TimelineManipulator.h"
#include "mementar/API/mementar/TimelinesManipulator.h"
#include "mementar/compat/ros.h"

namespace Ui { // NOLINT
Expand All @@ -30,11 +30,10 @@ class MementarGUI : public QMainWindow
private:
Ui::MementarGUI* ui_;

mementar::TimelineManipulator meme_;
mementar::TimelinesManipulator timelines_;
mementar::TimelineManipulator* timeline_;
bool multi_usage_;

std::map<std::string, std::unique_ptr<mementar::compat::mem_ros::Publisher<mementar::compat::StampedString>>> facts_publishers_;
std::map<std::string, std::unique_ptr<mementar::compat::mem_ros::Publisher<mementar::compat::MementarAction>>> actions_publishers_;
std::map<std::string, std::unique_ptr<mementar::compat::mem_ros::Subscriber<std_msgs_compat::String>>> feeder_notifications_subs_;
std::string feeder_notifications_;

int time_source_;
Expand Down Expand Up @@ -74,15 +73,17 @@ public slots:
void timesourceChangedSlot(int index);
void currentTimeEditingFinishedSlot();

void feederCallback(const std_msgs_compat::String& msg);
void feederCallback(const std::string& msg);
void feederAddSlot();
void feederDelSlot();
void feederCommitSlot();
void feederCheckoutSlot();
void createPublisher(const std::string& instance_ns);

bool updateTimelinePtr();

signals:
void feederSetHtmlSignal(QString);
void feederSetHtmlSignal(QString t1);
void feederScrollSignal(QString t1);
void setTimeSignal(QString);
};

Expand Down
10 changes: 9 additions & 1 deletion src/API/mementar/ActionsPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,10 @@

namespace mementar {

ActionsPublisher::ActionsPublisher(const std::string& name) : pub_(name.empty() ? "mementar/insert_action" : "mementar/insert_action/" + name, 1000) {}
ActionsPublisher::ActionsPublisher(const std::string& name) : feeder_notification_callback_([](auto& msg) { (void)msg; }),
pub_(name.empty() ? "mementar/insert_action" : "mementar/insert_action/" + name, 1000),
feeder_notif_sub_(name.empty() ? "mementar/feeder_notifications" : "mementar/feeder_notifications/" + name, 1000, &ActionsPublisher::feederNotificationCallback, this)
{}

void ActionsPublisher::insert(const std::string& name, time_t start_stamp, time_t end_stamp)
{
Expand Down Expand Up @@ -49,4 +52,9 @@ namespace mementar {
pub_.publish(msg);
}

void ActionsPublisher::feederNotificationCallback(const compat::mem_ros::MessageWrapper<std_msgs_compat::String>& msg)
{
feeder_notification_callback_(msg->data);
}

} // namespace mementar
11 changes: 2 additions & 9 deletions src/API/mementar/ActionsSubscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,8 @@
namespace mementar {

ActionsSubscriber::ActionsSubscriber(const std::function<void(const std::string&)>& callback,
const std::string& name,
bool spin_thread)
: OccasionsSubscriber([this](const Fact& fact) { this->privateCallback(fact); }, name, spin_thread),
callback_(callback)
{}

ActionsSubscriber::ActionsSubscriber(const std::function<void(const std::string&)>& callback,
bool spin_thread)
: OccasionsSubscriber([this](const Fact& fact) { this->privateCallback(fact); }, spin_thread),
const std::string& name)
: OccasionsSubscriber([this](const Fact& fact) { this->privateCallback(fact); }, name),
callback_(callback)
{}

Expand Down
27 changes: 25 additions & 2 deletions src/API/mementar/OccasionsPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,23 +4,46 @@
#include <string>

#include "mementar/API/mementar/Fact.h"
#include "mementar/compat/ros.h"

namespace mementar {

OccasionsPublisher::OccasionsPublisher(const std::string& name)
: pub_((name.empty()) ? "mementar/insert_fact_stamped" : "mementar/insert_fact_stamped/" + name, 1000) {}
OccasionsPublisher::OccasionsPublisher(const std::string& name) : feeder_notification_callback_([](auto& msg) { (void)msg; }),
pub_((name.empty()) ? "mementar/insert_fact_stamped" : "mementar/insert_fact_stamped/" + name, 1000),
feeder_notif_sub_(name.empty() ? "mementar/feeder_notifications" : "mementar/feeder_notifications/" + name, 1000, &OccasionsPublisher::feederNotificationCallback, this)
{}

void OccasionsPublisher::insert(const Fact& fact, compat::mem_ros::Time stamp)
{
publish(fact(), stamp);
}

void OccasionsPublisher::insert(const Fact& fact, time_t stamp)
{
publish(fact(), stamp);
}

void OccasionsPublisher::publish(const std::string& str, compat::mem_ros::Time stamp)
{
compat::StampedString msg;
msg.data = str;
msg.stamp.seconds = stamp.seconds();
msg.stamp.nanoseconds = stamp.nanoseconds();
pub_.publish(msg);
}

void OccasionsPublisher::publish(const std::string& str, time_t stamp)
{
compat::StampedString msg;
msg.data = str;
msg.stamp.seconds = stamp;
msg.stamp.nanoseconds = 0;
pub_.publish(msg);
}

void OccasionsPublisher::feederNotificationCallback(const compat::mem_ros::MessageWrapper<std_msgs_compat::String>& msg)
{
feeder_notification_callback_(msg->data);
}

} // namespace mementar
23 changes: 2 additions & 21 deletions src/API/mementar/OccasionsSubscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,35 +10,16 @@

namespace mementar {

OccasionsSubscriber::OccasionsSubscriber(const std::function<void(const Fact&)>& callback, const std::string& name, bool spin_thread)
OccasionsSubscriber::OccasionsSubscriber(const std::function<void(const Fact&)>& callback, const std::string& name)
: sub_(name.empty() ? "mementar/occasions" : "mementar/occasions/" + name, 1000, &OccasionsSubscriber::occasionCallback, this),
client_subscribe_(name.empty() ? "mementar/subscribe" : "mementar/subscribe/" + name),
client_cancel_(name.empty() ? "mementar/unsubscribe" : "mementar/unsubscribe/" + name),
callback_(callback)
{
(void)spin_thread;

/*if (spin_thread) {
need_to_terminate_ = false;
spin_thread_ = std::thread(std::bind(&OccasionsSubscriber::spinThread, this));
} else {
spin_thread_ = {};
}*/
}

OccasionsSubscriber::OccasionsSubscriber(const std::function<void(const Fact&)>& callback, bool spin_thread)
: OccasionsSubscriber(callback, "", spin_thread) {}
{}

OccasionsSubscriber::~OccasionsSubscriber()
{
cancel();
// todo
// sub_.shutdown();
/*if (spin_thread_) {
need_to_terminate_ = true;
spin_thread_->join();
delete spin_thread_;
}*/
}

bool OccasionsSubscriber::subscribe(const Fact& pattern, size_t count)
Expand Down
13 changes: 5 additions & 8 deletions src/RosInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,15 +115,12 @@ namespace mementar {
std::thread occasions_thread(&OccasionsManager::run, &occasions_);
std::thread feed_thread(&RosInterface::feedThread, this);

// ROS_DEBUG("%s mementar ready", name_.c_str());

while(compat::mem_ros::Node::ok() && isRunning())
{
// todo
// ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1));
}
if(name_.empty() == false)
Display::info("Mementar " + name_ + " is ready");
else
Display::info("Mementar is ready");

occasions_.stop();
// occasions_.stop(); // todo verify
occasions_thread.join();
feed_thread.join();
}
Expand Down
Loading

0 comments on commit 7a249ec

Please sign in to comment.