Skip to content

Commit

Permalink
[compat] use MessageWrapper for subscribers
Browse files Browse the repository at this point in the history
  • Loading branch information
sarthou committed Dec 21, 2023
1 parent c32991e commit 84aa48d
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 9 deletions.
4 changes: 2 additions & 2 deletions include/ontologenius/API/ontologenius/FeederPublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -186,8 +186,8 @@ class FeederPublisher
void publish(const std::string& str);
void publishStamped(const std::string& str, const ontologenius::compat::onto_ros::Time& stamp);

void commitCallback(const std_msgs_compat::String::ConstPtr& msg);
void notificationCallback(const std_msgs_compat::String::ConstPtr& msg);
void commitCallback(ontologenius::compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg);
void notificationCallback(ontologenius::compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg);
};

} // namespace onto
Expand Down
8 changes: 7 additions & 1 deletion include/ontologenius/compat/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,9 @@ namespace onto_ros
template <typename T>
using ServiceWrapper = T;

template <typename T>
using MessageWrapper = typename T::ConstPtr;

using Rate = ros::Rate;
using RosTime = ros::Time;

Expand All @@ -122,6 +125,9 @@ namespace onto_ros
template <typename T>
using ServiceWrapper = std::shared_ptr<T>;

template <typename T>
using MessageWrapper = typename T::ConstSharedPtr;

using Rate = rclcpp::Rate;
using RosTime = rclcpp::Time;

Expand Down Expand Up @@ -380,7 +386,7 @@ class Client
#if ONTO_ROS_VERSION == 1
return handle_.waitForExistence(ros::Duration(timeout));
#elif ONTO_ROS_VERSION == 2
return handle_->wait_for_service(timeout);
return handle_->wait_for_service(std::chrono::seconds(timeout));
#endif
}

Expand Down
4 changes: 2 additions & 2 deletions include/ontologenius/interface/RosInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,9 +110,9 @@ class RosInterface
bool display_;

/// @brief The ROS topic callback receiving statements not stamped
void knowledgeCallback(const std_msgs_compat::String::ConstPtr& msg);
void knowledgeCallback(compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg);
/// @brief The ROS topic callback receiving stamped statements
void stampedKnowledgeCallback(const compat::OntologeniusStampedString::ConstPtr& msg);
void stampedKnowledgeCallback(compat::onto_ros::MessageWrapper<compat::OntologeniusStampedString> msg);

/// @brief The ROS service callback in charge of general operations on the ontology
bool actionsHandle(compat::onto_ros::ServiceWrapper<compat::OntologeniusService::Request>& req,
Expand Down
4 changes: 2 additions & 2 deletions src/API/ontologenius/FeederPublisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,13 +180,13 @@ void FeederPublisher::publishStamped(const std::string& str, const ontologenius:
stamped_pub_.publish(msg);
}

void FeederPublisher::commitCallback(const std_msgs_compat::String::ConstPtr& msg)
void FeederPublisher::commitCallback(ontologenius::compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg)
{
if (msg->data == "end")
updated_ = true;
}

void FeederPublisher::notificationCallback(const std_msgs_compat::String::ConstPtr& msg)
void FeederPublisher::notificationCallback(ontologenius::compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg)
{
notification_callback_(msg->data);
}
Expand Down
4 changes: 2 additions & 2 deletions src/interface/RosInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,14 +198,14 @@ void RosInterface::setDisplay(bool display)
*
****************/

void RosInterface::knowledgeCallback(const std_msgs_compat::String::ConstPtr& msg)
void RosInterface::knowledgeCallback(compat::onto_ros::MessageWrapper<std_msgs_compat::String> msg)
{
auto now = compat::onto_ros::Node::get().current_time();

feeder_.store(msg->data, { (uint32_t) now.seconds(), (uint32_t) now.nanoseconds()});
}

void RosInterface::stampedKnowledgeCallback(const compat::OntologeniusStampedString::ConstPtr& msg)
void RosInterface::stampedKnowledgeCallback(compat::onto_ros::MessageWrapper<compat::OntologeniusStampedString> msg)
{
feeder_.store(msg->data, {msg->stamp.seconds, msg->stamp.nanoseconds});
}
Expand Down

0 comments on commit 84aa48d

Please sign in to comment.