Skip to content

Use int64_t as type for signal time. #109

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

Merged
merged 2 commits into from
Jul 28, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions src/converter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,11 @@ SOT_TO_ROS_IMPL(int) { dst.data = src; }

ROS_TO_SOT_IMPL(int) { dst = src.data; }

// Int64
SOT_TO_ROS_IMPL(int64_t) { dst.data = src; }

ROS_TO_SOT_IMPL(int64_t) { dst = src.data; }

// Unsigned
SOT_TO_ROS_IMPL(unsigned int) { dst.data = src; }

Expand Down Expand Up @@ -190,6 +195,7 @@ DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Twist, twist, ;);
DG_BRIDGE_MAKE_SHPTR_IMPL(bool);
DG_BRIDGE_MAKE_SHPTR_IMPL(double);
DG_BRIDGE_MAKE_SHPTR_IMPL(int);
DG_BRIDGE_MAKE_SHPTR_IMPL(int64_t);
DG_BRIDGE_MAKE_SHPTR_IMPL(unsigned int);
DG_BRIDGE_MAKE_SHPTR_IMPL(std::string);
DG_BRIDGE_MAKE_SHPTR_IMPL(Vector);
Expand Down
4 changes: 3 additions & 1 deletion src/ros_publish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ Value Add::doExecute() {
entity.add<unsigned int>(signal, topic);
else if (type == "int")
entity.add<int>(signal, topic);
else if (type == "int64")
entity.add<int64_t>(signal, topic);
else if (type == "matrix")
entity.add<Matrix>(signal, topic);
else if (type == "vector")
Expand Down Expand Up @@ -162,7 +164,7 @@ void RosPublish::clear() {
}
}

int& RosPublish::trigger(int& dummy, int t) {
int& RosPublish::trigger(int& dummy, sigtime_t t) {
typedef std::map<std::string, bindedSignal_t>::iterator iterator_t;
ros::Time aTime;
if (ros::Time::isSimTime()) {
Expand Down
11 changes: 6 additions & 5 deletions src/ros_publish.hh
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ class RosPublish : public dynamicgraph::Entity {
DYNAMIC_GRAPH_ENTITY_DECL();

public:
typedef boost::function<void(int)> callback_t;
typedef boost::function<void(sigtime_t)> callback_t;

typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
callback_t>
bindedSignal_t;

Expand All @@ -61,14 +61,15 @@ class RosPublish : public dynamicgraph::Entity {
std::vector<std::string> list() const;
void clear();

int& trigger(int&, int);
int& trigger(int&, sigtime_t);

template <typename T>
void sendData(
boost::shared_ptr<
realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
publisher,
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time);
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
sigtime_t time);

template <typename T>
void add(const std::string& signal, const std::string& topic);
Expand All @@ -77,7 +78,7 @@ class RosPublish : public dynamicgraph::Entity {
static const std::string docstring_;
ros::NodeHandle& nh_;
std::map<std::string, bindedSignal_t> bindedSignal_;
dynamicgraph::SignalTimeDependent<int, int> trigger_;
dynamicgraph::SignalTimeDependent<int, sigtime_t> trigger_;
ros::Duration rate_;
ros::Time nextPublication_;
boost::mutex mutex_;
Expand Down
5 changes: 3 additions & 2 deletions src/ros_publish.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ inline void RosPublish::sendData<std::pair<sot::MatrixHomogeneous, Vector> >(
boost::shared_ptr<
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalIn_t>
signal,
int time) {
sigtime_t time) {
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t result;
if (publisher->trylock()) {
publisher->msg_.child_frame_id = "/dynamic_graph/world";
Expand All @@ -31,7 +31,8 @@ void RosPublish::sendData(
boost::shared_ptr<
realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
publisher,
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time) {
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
sigtime_t time) {
typename SotToRos<T>::ros_t result;
if (publisher->trylock()) {
converter(publisher->msg_, signal->access(time));
Expand Down
2 changes: 1 addition & 1 deletion src/ros_queued_subscribe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ std::size_t RosQueuedSubscribe::queueSize(const std::string& signal) const {
return -1;
}

void RosQueuedSubscribe::readQueue(int beginReadingAt) {
void RosQueuedSubscribe::readQueue(int64_t beginReadingAt) {
// Prints signal queues sizes
/*for (std::map<std::string, bindedSignal_t>::const_iterator it =
bindedSignal_.begin (); it != bindedSignal_.end (); it++) {
Expand Down
16 changes: 8 additions & 8 deletions src/ros_queued_subscribe.hh
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ struct BindedSignalBase {

template <typename T, int BufferSize>
struct BindedSignal : BindedSignalBase {
typedef dynamicgraph::Signal<T, int> Signal_t;
typedef dynamicgraph::Signal<T, sigtime_t> Signal_t;
typedef boost::shared_ptr<Signal_t> SignalPtr_t;
typedef std::vector<T> buffer_t;
typedef typename buffer_t::size_type size_type;
Expand Down Expand Up @@ -132,7 +132,7 @@ struct BindedSignal : BindedSignalBase {

template <typename R>
void writer(const R& data);
T& reader(T& val, int time);
T& reader(T& val, sigtime_t time);

private:
/// Indicates whether the signal has received atleast one data point
Expand All @@ -159,7 +159,7 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
std::vector<std::string> listTopics();
void clear();
void clearQueue(const std::string& signal);
void readQueue(int beginReadingAt);
void readQueue(int64_t beginReadingAt);
std::size_t queueSize(const std::string& signal) const;
bool queueReceivedData(const std::string& signal) const;
void setQueueReceivedData(const std::string& signal, bool status);
Expand All @@ -176,12 +176,13 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
ros::NodeHandle& nh() { return nh_; }

template <typename R, typename S>
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
const R& data);
void callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data);

template <typename R>
void callbackTimestamp(
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
const R& data);

template <typename T>
Expand All @@ -193,8 +194,7 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
std::map<std::string, bindedSignal_t> bindedSignal_;
std::map<std::string, std::string> topics_;

int readQueue_;
// Signal<bool, int> readQueue_;
int64_t readQueue_;

template <typename T>
friend class internal::BindedSignal;
Expand Down
2 changes: 1 addition & 1 deletion src/ros_queued_subscribe.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ void BindedSignal<T, N>::writer(const R& data) {
}

template <typename T, int N>
T& BindedSignal<T, N>::reader(T& data, int time) {
T& BindedSignal<T, N>::reader(T& data, sigtime_t time) {
// synchronize with method clear:
// If reading from the list cannot be done, then return last value.
boost::mutex::scoped_lock lock(rmutex, boost::try_to_lock);
Expand Down
4 changes: 4 additions & 0 deletions src/ros_subscribe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,10 @@ Value Add::doExecute() {
entity.add<double>(signal, topic);
else if (type == "unsigned")
entity.add<unsigned int>(signal, topic);
else if (type == "int")
entity.add<int>(signal, topic);
else if (type == "int64")
entity.add<int64_t>(signal, topic);
else if (type == "matrix")
entity.add<dg::Matrix>(signal, topic);
else if (type == "vector")
Expand Down
9 changes: 5 additions & 4 deletions src/ros_subscribe.hh
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class RosSubscribe : public dynamicgraph::Entity {
typedef boost::posix_time::ptime ptime;

public:
typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
boost::shared_ptr<ros::Subscriber> >
bindedSignal_t;

Expand All @@ -71,12 +71,13 @@ class RosSubscribe : public dynamicgraph::Entity {
ros::NodeHandle& nh() { return nh_; }

template <typename R, typename S>
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
const R& data);
void callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data);

template <typename R>
void callbackTimestamp(
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
const R& data);

template <typename T>
Expand Down
8 changes: 5 additions & 3 deletions src/ros_subscribe.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@ namespace dg = dynamicgraph;
namespace dynamicgraph {
template <typename R, typename S>
void RosSubscribe::callback(
boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal, const R& data) {
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal,
const R& data) {
typedef S sot_t;
sot_t value;
converter(value, data);
Expand All @@ -27,7 +28,7 @@ void RosSubscribe::callback(

template <typename R>
void RosSubscribe::callbackTimestamp(
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
const R& data) {
ptime time = rosTimeToPtime(data->header.stamp);
signal->setConstant(time);
Expand Down Expand Up @@ -101,7 +102,8 @@ struct Add<std::pair<T, dg::Vector> > {
RosSubscribe.bindedSignal()[signal] = bindedSignal;

// Timestamp.
typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, int> signalTimestamp_t;
typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, sigtime_t>
signalTimestamp_t;
std::string signalTimestamp =
(boost::format("%1%%2%") % signal % "Timestamp").str();

Expand Down
4 changes: 2 additions & 2 deletions src/ros_tf_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
namespace dynamicgraph {
namespace internal {
sot::MatrixHomogeneous& TransformListenerData::getTransform(
sot::MatrixHomogeneous& res, int time) {
sot::MatrixHomogeneous& res, sigtime_t time) {
availableSig.recompute(time);

bool available = availableSig.accessCopy();
Expand All @@ -29,7 +29,7 @@ sot::MatrixHomogeneous& TransformListenerData::getTransform(
return res;
}

bool& TransformListenerData::isAvailable(bool& available, int time) {
bool& TransformListenerData::isAvailable(bool& available, sigtime_t time) {
static const ros::Time origin(0);
available = false;
ros::Duration elapsed;
Expand Down
11 changes: 6 additions & 5 deletions src/ros_tf_listener.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ class RosTfListener;

namespace internal {
struct TransformListenerData {
typedef SignalTimeDependent<bool, int> AvailableSignal_t;
typedef SignalTimeDependent<sot::MatrixHomogeneous, int> MatrixSignal_t;
typedef SignalPtr<sot::MatrixHomogeneous, int> DefaultSignal_t;
typedef SignalTimeDependent<bool, sigtime_t> AvailableSignal_t;
typedef SignalTimeDependent<sot::MatrixHomogeneous, sigtime_t> MatrixSignal_t;
typedef SignalPtr<sot::MatrixHomogeneous, sigtime_t> DefaultSignal_t;

RosTfListener* entity;
tf2_ros::Buffer& buffer;
Expand Down Expand Up @@ -52,9 +52,10 @@ struct TransformListenerData {
signal.addDependencies(failbackSig << availableSig);
}

sot::MatrixHomogeneous& getTransform(sot::MatrixHomogeneous& res, int time);
sot::MatrixHomogeneous& getTransform(sot::MatrixHomogeneous& res,
sigtime_t time);

bool& isAvailable(bool& isAvailable, int time);
bool& isAvailable(bool& isAvailable, sigtime_t time);
};
} // namespace internal

Expand Down
2 changes: 1 addition & 1 deletion src/ros_time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ RosTime::RosTime(const std::string& _name)
now_.setFunction(boost::bind(&RosTime::update, this, _1, _2));
}

ptime& RosTime::update(ptime& time, const int&) {
ptime& RosTime::update(ptime& time, const sigtime_t&) {
time = rosTimeToPtime(ros::Time::now());
return time;
}
Expand Down
4 changes: 2 additions & 2 deletions src/ros_time.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@ class RosTime : public dynamicgraph::Entity {
DYNAMIC_GRAPH_ENTITY_DECL();

public:
Signal<boost::posix_time::ptime, int> now_;
Signal<boost::posix_time::ptime, sigtime_t> now_;
RosTime(const std::string& name);
virtual std::string getDocString() const;

protected:
boost::posix_time::ptime& update(boost::posix_time::ptime& time,
const int& t);
const sigtime_t& t);

private:
static const std::string docstring_;
Expand Down
1 change: 1 addition & 0 deletions src/sot_to_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ namespace dynamicgraph {
const char* SotToRos<bool>::signalTypeName = "bool";
const char* SotToRos<double>::signalTypeName = "Double";
const char* SotToRos<int>::signalTypeName = "int";
const char* SotToRos<int64_t>::signalTypeName = "int64";
const char* SotToRos<std::string>::signalTypeName = "string";
const char* SotToRos<unsigned int>::signalTypeName = "Unsigned";
const char* SotToRos<Matrix>::signalTypeName = "Matrix";
Expand Down
Loading