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

Additional info on state changes of buttons #62

Open
wants to merge 3 commits into
base: development
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion src/baxter_interface/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ def __init__(self, name):

list_svc = rospy.ServiceProxy('/cameras/list', ListCameras)
rospy.wait_for_service('/cameras/list', timeout=10)
if not self._id in list_svc().cameras:
if not self._id in ["left_hand_camera","right_hand_camera","head_camera"]:
Copy link
Contributor

Choose a reason for hiding this comment

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

The robot will now list all 3 cameras as services, so I don't see the benefit in hard-coding the camera names here.

Copy link
Author

Choose a reason for hiding this comment

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

In the old SDK a roservice call /cameras/list listed you all available cameras. In the new version you get exactly the opened cameras which are left_hand_camera and right_hand_camera by default.

raise AttributeError(
("Cannot locate a service for camera name '{0}'. "
"Close a different camera first and try again.".format(self._id)))
Expand Down
2 changes: 1 addition & 1 deletion src/baxter_interface/digital_io.py
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ def _on_io_state(self, msg):

# trigger signal if changed
if old_state is not None and old_state != new_state:
self.state_changed(new_state)
self.state_changed(new_state,self._id)

@property
def is_output(self):
Expand Down
6 changes: 3 additions & 3 deletions src/baxter_interface/navigator.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,11 +177,11 @@ def _on_state(self, msg):
]
for i, signal in enumerate(buttons):
if old_state.buttons[i] != msg.buttons[i]:
signal(msg.buttons[i])
signal(msg.buttons[i],self._id,"button",i)

if old_state.wheel != msg.wheel:
diff = msg.wheel - old_state.wheel
if abs(diff % 256) < 127:
self.wheel_changed(diff % 256)
self.wheel_changed(diff % 256,self._id,"wheel",msg.wheel)
else:
self.wheel_changed(diff % (-256))
self.wheel_changed(diff % (-256),self._id,"wheel",msg.wheel)