Skip to content

Commit f7f362d

Browse files
Use int64_t as type for signal time.
1 parent 9e3d1f1 commit f7f362d

16 files changed

+109
-75
lines changed

src/converter.hh

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,11 @@ SOT_TO_ROS_IMPL(int) { dst.data = src; }
5252

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

55+
// Int64
56+
SOT_TO_ROS_IMPL(int64_t) { dst.data = src; }
57+
58+
ROS_TO_SOT_IMPL(int64_t) { dst = src.data; }
59+
5560
// Unsigned
5661
SOT_TO_ROS_IMPL(unsigned int) { dst.data = src; }
5762

@@ -190,6 +195,7 @@ DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Twist, twist, ;);
190195
DG_BRIDGE_MAKE_SHPTR_IMPL(bool);
191196
DG_BRIDGE_MAKE_SHPTR_IMPL(double);
192197
DG_BRIDGE_MAKE_SHPTR_IMPL(int);
198+
DG_BRIDGE_MAKE_SHPTR_IMPL(int64_t);
193199
DG_BRIDGE_MAKE_SHPTR_IMPL(unsigned int);
194200
DG_BRIDGE_MAKE_SHPTR_IMPL(std::string);
195201
DG_BRIDGE_MAKE_SHPTR_IMPL(Vector);

src/ros_publish.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,8 @@ Value Add::doExecute() {
5050
entity.add<unsigned int>(signal, topic);
5151
else if (type == "int")
5252
entity.add<int>(signal, topic);
53+
else if (type == "int64")
54+
entity.add<int64_t>(signal, topic);
5355
else if (type == "matrix")
5456
entity.add<Matrix>(signal, topic);
5557
else if (type == "vector")
@@ -162,7 +164,7 @@ void RosPublish::clear() {
162164
}
163165
}
164166

165-
int& RosPublish::trigger(int& dummy, int t) {
167+
int& RosPublish::trigger(int& dummy, sigtime_t t) {
166168
typedef std::map<std::string, bindedSignal_t>::iterator iterator_t;
167169
ros::Time aTime;
168170
if (ros::Time::isSimTime()) {

src/ros_publish.hh

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,9 @@ class RosPublish : public dynamicgraph::Entity {
4242
DYNAMIC_GRAPH_ENTITY_DECL();
4343

4444
public:
45-
typedef boost::function<void(int)> callback_t;
45+
typedef boost::function<void(sigtime_t)> callback_t;
4646

47-
typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
47+
typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
4848
callback_t>
4949
bindedSignal_t;
5050

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

64-
int& trigger(int&, int);
64+
int& trigger(int&, sigtime_t);
6565

6666
template <typename T>
6767
void sendData(
6868
boost::shared_ptr<
6969
realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
7070
publisher,
71-
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time);
71+
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
72+
sigtime_t time);
7273

7374
template <typename T>
7475
void add(const std::string& signal, const std::string& topic);
@@ -77,7 +78,7 @@ class RosPublish : public dynamicgraph::Entity {
7778
static const std::string docstring_;
7879
ros::NodeHandle& nh_;
7980
std::map<std::string, bindedSignal_t> bindedSignal_;
80-
dynamicgraph::SignalTimeDependent<int, int> trigger_;
81+
dynamicgraph::SignalTimeDependent<int, sigtime_t> trigger_;
8182
ros::Duration rate_;
8283
ros::Time nextPublication_;
8384
boost::mutex mutex_;

src/ros_publish.hxx

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,7 @@ inline void RosPublish::sendData<std::pair<sot::MatrixHomogeneous, Vector> >(
1616
publisher,
1717
boost::shared_ptr<
1818
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalIn_t>
19-
signal,
20-
int time) {
19+
signal, sigtime_t time) {
2120
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t result;
2221
if (publisher->trylock()) {
2322
publisher->msg_.child_frame_id = "/dynamic_graph/world";
@@ -31,7 +30,8 @@ void RosPublish::sendData(
3130
boost::shared_ptr<
3231
realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
3332
publisher,
34-
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time) {
33+
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
34+
sigtime_t time) {
3535
typename SotToRos<T>::ros_t result;
3636
if (publisher->trylock()) {
3737
converter(publisher->msg_, signal->access(time));

src/ros_queued_subscribe.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ std::size_t RosQueuedSubscribe::queueSize(const std::string& signal) const {
137137
return -1;
138138
}
139139

140-
void RosQueuedSubscribe::readQueue(int beginReadingAt) {
140+
void RosQueuedSubscribe::readQueue(int64_t beginReadingAt) {
141141
// Prints signal queues sizes
142142
/*for (std::map<std::string, bindedSignal_t>::const_iterator it =
143143
bindedSignal_.begin (); it != bindedSignal_.end (); it++) {

src/ros_queued_subscribe.hh

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ struct BindedSignalBase {
6666

6767
template <typename T, int BufferSize>
6868
struct BindedSignal : BindedSignalBase {
69-
typedef dynamicgraph::Signal<T, int> Signal_t;
69+
typedef dynamicgraph::Signal<T, sigtime_t> Signal_t;
7070
typedef boost::shared_ptr<Signal_t> SignalPtr_t;
7171
typedef std::vector<T> buffer_t;
7272
typedef typename buffer_t::size_type size_type;
@@ -132,7 +132,7 @@ struct BindedSignal : BindedSignalBase {
132132

133133
template <typename R>
134134
void writer(const R& data);
135-
T& reader(T& val, int time);
135+
T& reader(T& val, sigtime_t time);
136136

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

178178
template <typename R, typename S>
179-
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
180-
const R& data);
179+
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
180+
signal, const R& data);
181181

182182
template <typename R>
183183
void callbackTimestamp(
184-
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
184+
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
185185
const R& data);
186186

187187
template <typename T>
@@ -193,8 +193,7 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
193193
std::map<std::string, bindedSignal_t> bindedSignal_;
194194
std::map<std::string, std::string> topics_;
195195

196-
int readQueue_;
197-
// Signal<bool, int> readQueue_;
196+
int64_t readQueue_;
198197

199198
template <typename T>
200199
friend class internal::BindedSignal;

src/ros_queued_subscribe.hxx

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ void BindedSignal<T, N>::writer(const R& data) {
9292
}
9393

9494
template <typename T, int N>
95-
T& BindedSignal<T, N>::reader(T& data, int time) {
95+
T& BindedSignal<T, N>::reader(T& data, sigtime_t time) {
9696
// synchronize with method clear:
9797
// If reading from the list cannot be done, then return last value.
9898
boost::mutex::scoped_lock lock(rmutex, boost::try_to_lock);

src/ros_subscribe.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,10 @@ Value Add::doExecute() {
3636
entity.add<double>(signal, topic);
3737
else if (type == "unsigned")
3838
entity.add<unsigned int>(signal, topic);
39+
else if (type == "int")
40+
entity.add<int>(signal, topic);
41+
else if (type == "int64")
42+
entity.add<int64_t>(signal, topic);
3943
else if (type == "matrix")
4044
entity.add<dg::Matrix>(signal, topic);
4145
else if (type == "vector")

src/ros_subscribe.hh

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class RosSubscribe : public dynamicgraph::Entity {
4646
typedef boost::posix_time::ptime ptime;
4747

4848
public:
49-
typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
49+
typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
5050
boost::shared_ptr<ros::Subscriber> >
5151
bindedSignal_t;
5252

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

7373
template <typename R, typename S>
74-
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
75-
const R& data);
74+
void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
75+
signal, const R& data);
7676

7777
template <typename R>
7878
void callbackTimestamp(
79-
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
79+
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
8080
const R& data);
8181

8282
template <typename T>

src/ros_subscribe.hxx

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ namespace dg = dynamicgraph;
1818
namespace dynamicgraph {
1919
template <typename R, typename S>
2020
void RosSubscribe::callback(
21-
boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal, const R& data) {
21+
boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal, const R& data) {
2222
typedef S sot_t;
2323
sot_t value;
2424
converter(value, data);
@@ -27,7 +27,7 @@ void RosSubscribe::callback(
2727

2828
template <typename R>
2929
void RosSubscribe::callbackTimestamp(
30-
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
30+
boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
3131
const R& data) {
3232
ptime time = rosTimeToPtime(data->header.stamp);
3333
signal->setConstant(time);
@@ -101,7 +101,7 @@ struct Add<std::pair<T, dg::Vector> > {
101101
RosSubscribe.bindedSignal()[signal] = bindedSignal;
102102

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

0 commit comments

Comments
 (0)