Skip to content
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

rqt_plot: Plot bools #420

Closed
wants to merge 1 commit into from
Closed
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: 5 additions & 1 deletion rqt_plot/src/rqt_plot/rosplot.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
import roslib.message
import roslib.names
import rospy

import std_msgs.msg
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The package currently does not depend on std_msgs.


class RosPlotException(Exception):
pass
Expand Down Expand Up @@ -154,6 +154,10 @@ def _get_data(self, msg):
val = msg
try:
if not self.field_evals:
if type(val)==std_msgs.msg.Bool:
val = val.data
if type(val)==bool:
return 1.0 if val else 0.0
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These two lines are not necessary. The following line already achieve the same conversion: float(True) -> 1.0 and float(False) -> 1.0.

return float(val)
for f in self.field_evals:
val = f(val)
Expand Down