Skip to content

Commit

Permalink
Merge pull request #486 from mrdanbrooks/indigo-devel
Browse files Browse the repository at this point in the history
Implements delivered_msgs datafield to TopicStatistics.msg
  • Loading branch information
dirk-thomas committed Aug 18, 2014
2 parents 92efce7 + a6441ce commit 3745641
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 3 deletions.
4 changes: 2 additions & 2 deletions clients/roscpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<build_depend>rosconsole</build_depend>
<build_depend>roscpp_serialization</build_depend>
<build_depend version_gte="0.3.17">roscpp_traits</build_depend>
<build_depend version_gte="1.10.2">rosgraph_msgs</build_depend>
<build_depend version_gte="1.10.3">rosgraph_msgs</build_depend>
<build_depend>roslang</build_depend>
<build_depend>rostime</build_depend>
<build_depend>std_msgs</build_depend>
Expand All @@ -40,7 +40,7 @@
<run_depend>rosconsole</run_depend>
<run_depend>roscpp_serialization</run_depend>
<run_depend version_gte="0.3.17">roscpp_traits</run_depend>
<run_depend>rosgraph_msgs</run_depend>
<run_depend version_gte="1.10.3">rosgraph_msgs</run_depend>
<run_depend>rostime</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>xmlrpcpp</run_depend>
Expand Down
1 change: 1 addition & 0 deletions clients/roscpp/src/libros/statistics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,7 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
msg.node_sub = ros::this_node::getName();
msg.window_start = window_start;
msg.window_stop = received_time;
msg.delivered_msgs = stats.arrival_time_list.size();
msg.dropped_msgs = stats.dropped_msgs;
msg.traffic = bytes_sent - stats.stat_bytes_last;

Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
<run_depend>python-yaml</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rosgraph</run_depend>
<run_depend>rosgraph_msgs</run_depend>
<run_depend version_gte="1.10.3">rosgraph_msgs</run_depend>
<run_depend>roslib</run_depend>
<run_depend>std_msgs</run_depend>

Expand Down
1 change: 1 addition & 0 deletions clients/rospy/src/rospy/impl/statistics.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@ def sendStatistics(self, subscriber_statistics_logger):

msg.traffic = self.stat_bytes_window_

msg.delivered_msgs = len(self.arrival_time_list_)
msg.dropped_msgs = self.dropped_msgs_

# we can only calculate message age if the messages did contain Header fields.
Expand Down

0 comments on commit 3745641

Please sign in to comment.