Skip to content

Commit

Permalink
Fix some of Alvin's small comments
Browse files Browse the repository at this point in the history
  • Loading branch information
AndrewHWang1605 committed Mar 13, 2024
1 parent bbe2697 commit 9cf5864
Show file tree
Hide file tree
Showing 4 changed files with 1 addition and 25 deletions.
2 changes: 1 addition & 1 deletion ff_control/ff_control/tri_thruster_ctrl.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# MIT License
#
# Copyright (c) 2023 Stanford Autonomous Systems Lab
# Copyright (c) 2024 Stanford Autonomous Systems Lab
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
Expand Down
3 changes: 0 additions & 3 deletions ff_control/ff_control/wrench_ctrl.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,6 @@ def set_body_wrench(self, wrench_body: Wrench2D, use_wheel: bool = False) -> Non
wrench_body_clipped = self.clip_wrench(wrench_body)

# convert force
self.get_logger().info(
"Checking value of actuators" + str(self.p.actuators["F_max_per_thruster"])
)
u_Fx = wrench_body_clipped.fx / (2 * self.p.actuators["F_max_per_thruster"])
u_Fy = wrench_body_clipped.fy / (2 * self.p.actuators["F_max_per_thruster"])
if u_Fx > 0:
Expand Down
14 changes: 0 additions & 14 deletions ff_sim/ff_sim/simulator_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@
Wrench2DStamped,
WheelVelCommand,
ThrusterCommand,
ControllerMetrics,
)

from ff_params import RobotParams
Expand Down Expand Up @@ -117,16 +116,6 @@ def __init__(self):

self.p = RobotParams(self)

self.running_total_gas = 0
self.thrust_hist = [[] for i in range(8)]
self.thrust_duty_cycles = [0] * 8
# self.start_time = self.get_clock().now().to_msg()
self.steps = 0
self.duty_cycle_window = 200
self.rolled_up = False
# self.get_logger().info("********MESSAGE"+str(self.start_time))
# self.get_logger().info("********SEC"+str(self.start_time.sec))

# obstacles
p_obstacles = self.declare_parameters(
"obstacles",
Expand Down Expand Up @@ -191,9 +180,6 @@ def __init__(self):
self.declare_parameter("mocap_noise_xy", 0.001)
self.declare_parameter("mocap_noise_theta", math.radians(0.1))
self.pub_mocap = self.create_publisher(PoseStamped, "mocap/sim/pose", 10)
self.pub_controller_metrics = self.create_publisher(
ControllerMetrics, "controller/metrics", 10
)

self.sim_timer = self.create_timer(self.SIM_DT, self.sim_loop)

Expand Down
7 changes: 0 additions & 7 deletions freeflyer/test/opt_ctrl_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,6 @@ def generate_test_description():
name="opt_ctrl_node",
namespace=ROBOT_NAME,
)
# pwm_ctrl_node = Node(
# package="ff_control",
# executable=["pwm_ctrl_cpp_node"],
# name="pwm_ctrl_node",
# namespace=ROBOT_NAME,
# condition=IfCondition(PythonExpression(["'", impl, "'", " == 'py'"])),
# )
estimator = Node(
package="ff_estimate",
executable="moving_avg_estimator_node",
Expand Down

0 comments on commit 9cf5864

Please sign in to comment.