Skip to content

Commit

Permalink
Kimberly's feedback:
Browse files Browse the repository at this point in the history
1) unused code removal
2) Better error handling of tf errors

3) Improved handling of simulation time
4) Unified error handling in on_timer
  • Loading branch information
whoenig committed Feb 6, 2024
1 parent 55e11da commit 60524ac
Show file tree
Hide file tree
Showing 2 changed files with 49 additions and 37 deletions.
4 changes: 4 additions & 0 deletions crazyflie/launch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -138,5 +138,9 @@ def generate_launch_description():
package='crazyflie',
executable='gui.py',
name='gui',
output='screen',
parameters=[{
"use_sim_time": True,
}]
),
])
82 changes: 45 additions & 37 deletions crazyflie/scripts/gui.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,6 @@ def __init__(self) -> None:
self.battery_labels = dict()
self.radio_labels = dict()
self.robotmodels = dict()
# set of robot names that had a status recently
self.watchdog = dict()

with Client.auto_index_client:

Expand All @@ -60,11 +58,13 @@ def __init__(self) -> None:
for name in self.cfnames:
robot = scene.stl('/urdf/cf2_assembly.stl').scale(1.0).material('#ff0000').with_name(name)
self.robotmodels[name] = robot
self.watchdog[name] = time.time()
# augment with some additional fields
robot.status_ok = False
robot.status_watchdog = time.time()
scene.camera.x = 0
scene.camera.y = -1
scene.camera.z = 2
scene.camera.look_at_x = 0
scene.camera.look_at_x = 0
scene.camera.look_at_y = 0
scene.camera.look_at_z = 0

Expand All @@ -80,21 +80,16 @@ def __init__(self) -> None:
self.supervisor_labels[name] = ui.label("")
self.battery_labels[name] = ui.label("")
self.radio_labels[name] = ui.label("")
ui.button("Reboot", on_click=partial(self.on_reboot, name=name))

for name in self.cfnames:
self.create_subscription(Status, name + '/status', partial(self.on_status, name=name), 1)

# Call on_timer function
self.timer = self.create_timer(0.1, self.on_timer)

def send_speed(self, x: float, y: float) -> None:
msg = Twist()
msg.linear.x = x
msg.angular.z = -y
self.linear.value = x
self.angular.value = y
self.cmd_vel_publisher.publish(msg)
update_rate = 30 # Hz
self.timer = self.create_timer(
1.0/update_rate,
self.on_timer,
clock=rclpy.clock.Clock(clock_type=rclpy.clock.ClockType.SYSTEM_TIME))

def on_rosout(self, msg: Log) -> None:
# filter by crazyflie and add to the correct log
Expand All @@ -115,20 +110,38 @@ def on_rosout(self, msg: Log) -> None:

def on_timer(self) -> None:
for name, robotmodel in self.robotmodels.items():
t = self.tf_buffer.lookup_transform(
"world",
name,
rclpy.time.Time())
pos = t.transform.translation
robotmodel.move(pos.x, pos.y, pos.z)
robotmodel.rotate(*rowan.to_euler([
t.transform.rotation.w,
t.transform.rotation.x,
t.transform.rotation.y,
t.transform.rotation.z], "xyz"))

# no update for a while -> mark red
if time.time() - self.watchdog[name] > 2.0:
ros_time = rclpy.time.Time() # get the latest
robot_status_ok = robotmodel.status_ok
if self.tf_buffer.can_transform("world", name, ros_time):
t = self.tf_buffer.lookup_transform(
"world",
name,
ros_time)
transform_time = rclpy.time.Time.from_msg(t.header.stamp)
transform_age = self.get_clock().now() - transform_time
# latest transform is older than a second indicates a problem
if transform_age.nanoseconds * 1e-9 > 1:
robot_status_ok = False
else:
pos = t.transform.translation
robotmodel.move(pos.x, pos.y, pos.z)
robotmodel.rotate(*rowan.to_euler([
t.transform.rotation.w,
t.transform.rotation.x,
t.transform.rotation.y,
t.transform.rotation.z], "xyz"))
else:
# no available transform indicates a problem
robot_status_ok = False

# no status update for a while, indicate a problem
if time.time() - robotmodel.status_watchdog > 2.0:
robot_status_ok = False

# any issues detected -> mark red, otherwise green
if robot_status_ok:
robotmodel.material('#00ff00')
else:
robotmodel.material('#ff0000')

def on_vis_click(self, e: events.SceneClickEventArguments):
Expand Down Expand Up @@ -181,13 +194,11 @@ def on_status(self, msg, name) -> None:
radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}'
self.radio_labels[name].set_text(radio_text)

if status_ok:
self.robotmodels[name].material('#00ff00')
else:
self.robotmodels[name].material('#ff0000')

self.watchdog[name] = time.time()
# save status here
self.robotmodels[name].status_ok = status_ok

# store the time when we last received any status
self.robotmodels[name].status_watchdog[name] = time.time()

def on_tab_change(self, arg):
for name, robotmodel in self.robotmodels.items():
Expand All @@ -196,9 +207,6 @@ def on_tab_change(self, arg):
if arg.value in self.robotmodels:
self.robotmodels[arg.value].scale(2)

def on_reboot(self, name) -> None:
ui.notify(f'Reboot not implemented, yet')


def main() -> None:
# NOTE: This function is defined as the ROS entry point in setup.py, but it's empty to enable NiceGUI auto-reloading
Expand Down

0 comments on commit 60524ac

Please sign in to comment.