Skip to content

Commit 0e7191c

Browse files
author
Rabia Aslam
committed
Merge branch 'feature/new-rvr-sdk-cmds' into 'develop'
Feature/new rvr sdk cmds See merge request sdk/v4/convenience/raspberry-pi!73
2 parents a3813cc + e6582f9 commit 0e7191c

24 files changed

+529
-25
lines changed

getting_started/asyncio/driving/control_system_selection.py

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -106,11 +106,13 @@ async def main():
106106
# Delay to allow RVR to drive
107107
await asyncio.sleep(1)
108108

109-
# Set the default control system for RC and drive some more
110-
control_system_type = ControlSystemTypesEnum.control_system_type_rc_drive
111-
controller_id = ControlSystemIdsEnum.rc_drive_rate_mode
112-
print('Setting default control system for RC drive to {}'.format(controller_id.name))
113-
await rvr.set_default_control_system_for_type(control_system_type = control_system_type, controller_id = controller_id)
109+
# Stop the robot
110+
print('Stopping...')
111+
await rvr.stop_active_controller()
112+
113+
# Restore initial default control systems
114+
print('Restore initial default control systems')
115+
await rvr.restore_initial_default_control_systems()
114116

115117
print('Driving with RC...')
116118
await rvr.drive_rc_si_units(linear_velocity=1, yaw_angular_velocity=0, flags=0 )
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
import os
2+
import sys
3+
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '../../../')))
4+
5+
import asyncio
6+
from sphero_sdk import SpheroRvrAsync
7+
from sphero_sdk import SerialAsyncDal
8+
9+
10+
loop = asyncio.get_event_loop()
11+
12+
rvr = SpheroRvrAsync(
13+
dal=SerialAsyncDal(
14+
loop
15+
)
16+
)
17+
18+
19+
async def main():
20+
""" This program demonstrates how to get encoder counts on RVR.
21+
"""
22+
23+
await rvr.wake()
24+
25+
# Give RVR time to wake up
26+
await asyncio.sleep(2)
27+
28+
encoder_counts = await rvr.get_encoder_counts()
29+
print('Encoder counts: ', encoder_counts)
30+
31+
await rvr.close()
32+
33+
34+
if __name__ == '__main__':
35+
try:
36+
loop.run_until_complete(
37+
main()
38+
)
39+
40+
except KeyboardInterrupt:
41+
print('\nProgram terminated with keyboard interrupt.')
42+
43+
loop.run_until_complete(
44+
rvr.close()
45+
)
46+
47+
finally:
48+
if loop.is_running():
49+
loop.close()

getting_started/asyncio/magnetometer/__init__.py

Whitespace-only changes.
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
import os
2+
import sys
3+
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '../../../')))
4+
5+
import asyncio
6+
from sphero_sdk import SpheroRvrAsync
7+
from sphero_sdk import SerialAsyncDal
8+
9+
10+
loop = asyncio.get_event_loop()
11+
12+
rvr = SpheroRvrAsync(
13+
dal=SerialAsyncDal(
14+
loop
15+
)
16+
)
17+
18+
19+
async def main():
20+
""" This program demonstrates how to get a reading from the magnetometer on RVR.
21+
"""
22+
23+
await rvr.wake()
24+
25+
# Give RVR time to wake up
26+
await asyncio.sleep(2)
27+
28+
magnetometer_reading = await rvr.get_magnetometer_reading()
29+
print('Magnetometer reading: ', magnetometer_reading)
30+
31+
await rvr.close()
32+
33+
34+
if __name__ == '__main__':
35+
try:
36+
loop.run_until_complete(
37+
main()
38+
)
39+
40+
except KeyboardInterrupt:
41+
print('\nProgram terminated with keyboard interrupt.')
42+
43+
loop.run_until_complete(
44+
rvr.close()
45+
)
46+
47+
finally:
48+
if loop.is_running():
49+
loop.close()
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
import os
2+
import sys
3+
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '../../../')))
4+
5+
import asyncio
6+
from sphero_sdk import SpheroRvrAsync
7+
from sphero_sdk import SerialAsyncDal
8+
9+
10+
loop = asyncio.get_event_loop()
11+
12+
rvr = SpheroRvrAsync(
13+
dal=SerialAsyncDal(
14+
loop
15+
)
16+
)
17+
18+
# Flag used to indicate that calibration is complete
19+
calibration_completed = False
20+
21+
# Handler for completion of calibration
22+
async def on_calibration_complete_notify_handler(response):
23+
global calibration_completed
24+
25+
print('Calibration complete, response:', response)
26+
calibration_completed = True
27+
28+
29+
async def main():
30+
""" This program demonstrates the magnetometer calibration to find north.
31+
"""
32+
33+
global calibration_completed
34+
35+
await rvr.wake()
36+
37+
# Give RVR time to wake up
38+
await asyncio.sleep(2)
39+
40+
# Register for the async on completion of calibration
41+
await rvr.on_magnetometer_calibration_complete_notify(handler=on_calibration_complete_notify_handler)
42+
43+
# Begin calibration
44+
print('Begin magnetometer calibration to find North...')
45+
await rvr.magnetometer_calibrate_to_north()
46+
47+
# Wait to complete the calibration. Note: In a real project, a timeout mechanism
48+
# should be here to prevent the script from getting caught in an infinite loop
49+
while (calibration_completed == False):
50+
await asyncio.sleep(0)
51+
52+
await rvr.close();
53+
54+
55+
if __name__ == '__main__':
56+
try:
57+
loop.run_until_complete(
58+
main()
59+
)
60+
61+
except KeyboardInterrupt:
62+
print('\nProgram terminated with keyboard interrupt.')
63+
64+
loop.run_until_complete(
65+
asyncio.gather(
66+
rvr.disable_notifications_and_active_commands(),
67+
rvr.close()
68+
)
69+
)
70+
71+
finally:
72+
if loop.is_running():
73+
loop.close()
Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
import os
2+
import sys
3+
sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '../../../')))
4+
5+
import asyncio
6+
from sphero_sdk import SpheroRvrAsync
7+
from sphero_sdk import SerialAsyncDal
8+
from sphero_sdk import RvrStreamingServices
9+
10+
11+
loop = asyncio.get_event_loop()
12+
13+
rvr = SpheroRvrAsync(
14+
dal=SerialAsyncDal(
15+
loop
16+
)
17+
)
18+
19+
20+
async def imu_handler(imu_data):
21+
print('IMU data response: ', imu_data)
22+
23+
24+
async def color_detected_handler(color_detected_data):
25+
print('Color detection data response: ', color_detected_data)
26+
27+
28+
async def main():
29+
""" This program demonstrates how to disable all notifications and active commands.
30+
"""
31+
32+
await rvr.wake()
33+
34+
# Give RVR time to wake up
35+
await asyncio.sleep(2)
36+
37+
print('Initiate streaming IMU and color sensor data...')
38+
await rvr.enable_color_detection(is_enabled=True)
39+
await rvr.sensor_control.add_sensor_data_handler(
40+
service=RvrStreamingServices.imu,
41+
handler=imu_handler
42+
)
43+
await rvr.sensor_control.add_sensor_data_handler(
44+
service=RvrStreamingServices.color_detection,
45+
handler=color_detected_handler
46+
)
47+
await rvr.sensor_control.start(interval=1000)
48+
49+
print('Set the control system timeout to 10s and initiate a drive command...')
50+
await rvr.set_custom_control_system_timeout(command_timeout=10000)
51+
await rvr.drive_with_yaw_normalized(
52+
linear_velocity=32, # Valid linear_velocity values are in the range [-127..+127]
53+
yaw_angle=0 # Valid yaw values are traditionally [-179..+180], but will continue wrapping outside of that range
54+
)
55+
56+
# Delay to allow commands to run
57+
await asyncio.sleep(5)
58+
59+
# Disable notifications and active commands
60+
await rvr.disable_notifications_and_active_commands()
61+
print('Disabling notifications and active commands...')
62+
63+
# Delay to allow observation that notifications and active commands have been disabled
64+
await asyncio.sleep(5)
65+
66+
# Restore the default timeout (2 seconds)
67+
await rvr.restore_default_control_system_timeout()
68+
69+
await rvr.close()
70+
71+
72+
if __name__ == '__main__':
73+
try:
74+
loop.run_until_complete(
75+
main()
76+
)
77+
78+
except KeyboardInterrupt:
79+
print('\nProgram terminated with keyboard interrupt.')
80+
81+
loop.run_until_complete(
82+
asyncio.gather(
83+
rvr.disable_notifications_and_active_commands(),
84+
# Restore the default timeout (2 seconds)
85+
rvr.restore_default_control_system_timeout(),
86+
rvr.close()
87+
)
88+
)
89+
90+
finally:
91+
if loop.is_running():
92+
loop.close()

sphero_sdk/asyncio/client/toys/sphero_rvr_async.py

Lines changed: 68 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22
# This file is automatically generated!
33
# Toy Name: Sphero RVR
44
# Prefix: RV
5-
# Command Count: 86
6-
# Timestamp: 05/19/2020 @ 15:46:04.409781 (UTC)
5+
# Command Count: 92
6+
# Timestamp: 05/30/2020 @ 00:36:04.915980 (UTC)
77

88
import asyncio
99
import logging.config
@@ -647,6 +647,15 @@ async def get_active_control_system_id(self, timeout=None):
647647
command_dict = drive.get_active_control_system_id(target=2, timeout=timeout)
648648
return await self._dal.send_command(**command_dict)
649649

650+
async def restore_initial_default_control_systems(self, timeout=None):
651+
"""Restore initial default control systems.
652+
653+
Args:
654+
timeout (float): maximum time to await a response.
655+
"""
656+
command_dict = drive.restore_initial_default_control_systems(target=2, timeout=timeout)
657+
return await self._dal.send_command(**command_dict)
658+
650659
async def get_default_control_system_for_type(self, control_system_type, timeout=None):
651660
"""Get the ID of the default control system for the given type
652661
@@ -729,6 +738,15 @@ async def get_rgbc_sensor_values(self, timeout=None):
729738
command_dict = sensor.get_rgbc_sensor_values(target=1, timeout=timeout)
730739
return await self._dal.send_command(**command_dict)
731740

741+
async def magnetometer_calibrate_to_north(self, timeout=None):
742+
"""Start magnetometer calibration to find north.
743+
744+
Args:
745+
timeout (float): maximum time to await a response.
746+
"""
747+
command_dict = sensor.magnetometer_calibrate_to_north(target=2, timeout=timeout)
748+
return await self._dal.send_command(**command_dict)
749+
732750
async def start_robot_to_robot_infrared_broadcasting(self, far_code, near_code, timeout=None):
733751
"""For robot following, broadcasting robots emit two codes: one for long distance (3 meters +), and one for short distance (< 1 meter). Following robots use both of these codes to determine direction and distance from the broadcasting robot.
734752
@@ -996,6 +1014,54 @@ async def on_motor_thermal_protection_status_notify(self, handler=None, timeout=
9961014
self._dal.on_command(**command_dict)
9971015
)
9981016

1017+
async def on_magnetometer_calibration_complete_notify(self, handler=None, timeout=None):
1018+
"""Magnetometer calibration complete notify.
1019+
1020+
Args:
1021+
handler (function): called asynchronously, takes form handler(isSuccessful, yawNorthDirection).
1022+
timeout (float): maximum time to await a response.
1023+
Returns:
1024+
Task (Future) from which `handler` will be called
1025+
"""
1026+
command_dict = sensor.on_magnetometer_calibration_complete_notify(target=2, timeout=timeout)
1027+
command_dict['handler'] = handler
1028+
return asyncio.ensure_future(
1029+
self._dal.on_command(**command_dict)
1030+
)
1031+
1032+
async def get_magnetometer_reading(self, timeout=None):
1033+
"""Get current magnetometer reading.
1034+
1035+
Args:
1036+
timeout (float): maximum time to await a response.
1037+
1038+
Returns:
1039+
dict: x_axis (float), y_axis (float), z_axis (float)
1040+
"""
1041+
command_dict = sensor.get_magnetometer_reading(target=2, timeout=timeout)
1042+
return await self._dal.send_command(**command_dict)
1043+
1044+
async def get_encoder_counts(self, timeout=None):
1045+
"""Get array of all encoder counts. Returned as left wheel and then right wheel encoder counts.
1046+
1047+
Args:
1048+
timeout (float): maximum time to await a response.
1049+
1050+
Returns:
1051+
dict: encoder_counts (list(int32_t))
1052+
"""
1053+
command_dict = sensor.get_encoder_counts(target=2, timeout=timeout)
1054+
return await self._dal.send_command(**command_dict)
1055+
1056+
async def disable_notifications_and_active_commands(self, timeout=None):
1057+
"""Disable notifications and active commands.
1058+
1059+
Args:
1060+
timeout (float): maximum time to await a response.
1061+
"""
1062+
command_dict = sensor.disable_notifications_and_active_commands(target=1, timeout=timeout)
1063+
return await self._dal.send_command(**command_dict)
1064+
9991065
async def get_bluetooth_advertising_name(self, timeout=None):
10001066
"""Returns null-terminated string with the BLE advertising name (e.g., "BL-ABCD").
10011067

sphero_sdk/common/commands/api_and_shell.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
# Source File: 0x10-api_and_shell.json
44
# Device ID: 0x10
55
# Device Name: api_and_shell
6-
# Timestamp: 05/19/2020 @ 15:46:04.396461 (UTC)
6+
# Timestamp: 05/30/2020 @ 00:36:04.905021 (UTC)
77

88
from sphero_sdk.common.enums.api_and_shell_enums import CommandsEnum
99
from sphero_sdk.common.devices import DevicesEnum

0 commit comments

Comments
 (0)