Open ablasdel opened 11 years ago
file changes in ROS 1.1 trunk
Index: stacks/ros/trunk/core/roslib/src/roslib/message.py
===================================================================
--- a/stacks/ros/trunk/core/roslib/src/roslib/message.py
+++ b/stacks/ros/trunk/core/roslib/src/roslib/message.py
@@ -150,5 +150,5 @@
# we expose the generic message-strify routine for fn-oriented code like rostopic
-def strify_message(val, indent='', time_offset=None):
+def strify_message(val, indent='', time_offset=None, current_time=None):
"""
convert value to string representation
@@ -160,4 +160,6 @@
as deltas from time_offset
@type time_offset: Time
+ @param current_time: currently not used. Only provided for API compatibility. current_time passes in the current time with respect to the message.
+ @type current_time: Time
"""
if type(val) in [int, long, float, str, bool]:
Index: stacks/ros/trunk/tools/rosmake/src/rosmake/rosmake.py
===================================================================
--- a/stacks/ros/trunk/tools/rosmake/src/rosmake/rosmake.py
+++ b/stacks/ros/trunk/tools/rosmake/src/rosmake/rosmake.py
@@ -95,5 +95,6 @@
self.verbose = False
self.full_verbose = False
- self.duration = 1./60.
+ self.duration = 1./5.
+ self._last_status = None
# Rosmake specific data
@@ -130,5 +131,7 @@
if n > 0:
status = " "*n + self.status
- self._print_status("%s"%status)
+ if status != self._last_status:
+ self._print_status("%s"%status)
+ self._last_status = status
time.sleep(self.duration)
self.done = True
@@ -677,5 +680,5 @@
action="store_true", help="do not build a package unless it is marked as supported on this platform, and all dependents are also marked")
parser.add_option("--status-rate", dest="status_update_rate",
- action="store", help="How fast to update the status bar in Hz. Default: 60Hz")
+ action="store", help="How fast to update the status bar in Hz. Default: 5Hz")
Index: stacks/ros/trunk/tools/rostopic/src/rostopic.py
===================================================================
--- a/stacks/ros/trunk/tools/rostopic/src/rostopic.py
+++ b/stacks/ros/trunk/tools/rostopic/src/rostopic.py
@@ -417,5 +417,5 @@
-def _str_plot(val, time_offset=None):
+def _str_plot(val, time_offset=None, current_time=None):
"""
convert value to matlab/octave-friendly CSV string representation.
@@ -424,4 +424,8 @@
@param val: message
@type val: Message
+ @param current_time: current time to use if message does not contain its own timestamp.
+ @type current_time: roslib.rostime.Time
+ @param time_offset: (optional) for time printed for message, print as offset against this time
+ @type time_offset: roslib.rostime.Time
@return: comma-separated list of field values in val
@rtype: str
@@ -435,6 +439,9 @@
if getattr(val, "_has_header", False):
return "%s,%s"%(val.header.stamp.to_nsec()-time_offset, s)
+ elif current_time is not None:
+ return "%s,%s"%(current_time.to_nsec()-time_offset, s)
else:
return "%s,%s"%(rospy.get_rostime().to_nsec()-time_offset, s)
+
#TODO: get rid of the ugly use of the _echo_nonostr and _echo_noarr
@@ -522,5 +529,5 @@
self.last_msg_eval = None
- def callback(self, data, topic):
+ def callback(self, data, topic, current_time=None):
"""
Callback to pass to rospy.Subscriber or to call
@@ -530,5 +537,7 @@
@type data: Message
@param topic: topic name
- @type topic: str
+ @type topic: str
+ @param current_time: override calculation of current time
+ @type current_time: roslib.rostime.Time
"""
if self.filter_fn is not None and not self.filter_fn(data):
@@ -571,7 +580,7 @@
if self.offset_time:
- sys.stdout.write(self.sep+self.str_fn(data, time_offset=rospy.get_rostime()) + '\n')
+ sys.stdout.write(self.sep+self.str_fn(data, time_offset=rospy.get_rostime(), current_time=current_time) + '\n')
else:
- sys.stdout.write(self.sep+self.str_fn(data) + '\n')
+ sys.stdout.write(self.sep+self.str_fn(data, current_time=current_time) + '\n')
#sys.stdout.flush()
@@ -606,10 +615,10 @@
raise ROSTopicException("bag file [%s] does not exist"%bag_file)
first = True
- for t, msg, _ in rosrecord.logplayer(bag_file):
+ for t, msg, timestamp in rosrecord.logplayer(bag_file):
# bag files can have relative paths in them, this respects any
# dynamic renaming
if t[0] != '/':
t = roslib.scriptutil.script_resolve_name('rostopic', t)
- callback_echo.callback(msg, t)
+ callback_echo.callback(msg, t, current_time=timestamp)
# done is set if there is a max echo count
if callback_echo.done:
The current time is of little real value when extracting messages from a bagfile, whereas the time returned from the bag is very appropriate.
I expect this is just the way it is since -b was added at a later point in time.
change history added (jan 8 2013): Changed 3 years ago by kwc ROS 1.1 trunk: https://code.ros.org/trac/ros/changeset/9996
migrated from trac ticket 3429: https://code.ros.org/trac/ros/ticket/3429