Skip to content

Commit

Permalink
feat: cast type now applied regardless of profile peak. Fix log messa…
Browse files Browse the repository at this point in the history
…ge in arm_base.
  • Loading branch information
figuernd committed Apr 1, 2024
1 parent a5b529b commit 8c780b6
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 34 deletions.
32 changes: 16 additions & 16 deletions configs/example.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -134,35 +134,35 @@ arm_ifcb:
arm_chanos:
tasks:
dwell_time: 60 # seconds
# For continuous movements (no steps), a speed can be specified.
continuous_speed: 0.005
# must be "stepped" or "continuous"
downcast_type: "stepped"
upcast_type: "continuous"
profiler_peak:
# If true, will use the profiler to find the peak value
# Falls back on default_movement values otherwise
# Falls back on default_steps otherwise
enabled: true
# Minimum level of the profiled sensor data to trigger a sample at depth
threshold: 0.0
# seconds since last peak to consider it expired
peak_expiration: 60
# Stops to be made relative to profiler_peak
offset_steps:
- -0.5
- -0.5 # meters
- -0.25
- 0.0
- 0.25
- 0.5
default_movement:
# Steps will be sorted in direction of movement.
absolute_steps:
- 0.5
- 2.0
- 3.0
- 4.0
- 5.0
- 6.5
# For continuous movements (no steps), a speed can be specified.
continuous_speed: 0.005
# must be "stepped" or "continuous"
downcast_type: "stepped"
upcast_type: "continuous"
# Absolute depths to use if profiler_peak not enabeld
# Steps will be sorted in direction of movement.
default_steps:
- 0.5 # meters
- 2.0
- 3.0
- 4.0
- 5.0
- 6.5

ctd_topic: '/arm_chanos/ctd/depth'

Expand Down
2 changes: 1 addition & 1 deletion src/phyto_arm/src/arm_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ def send_winch_goal(self, depth, speed, callback):

# Safety check: Do not exceed depth bounds
if depth < rospy.get_param('winch/range/min'):
raise ValueError(f'Move aborted: depth {depth} is below min {rospy.get_param("winch/range/max")}')
raise ValueError(f'Move aborted: depth {depth} is below min {rospy.get_param("winch/range/min")}')
elif depth > rospy.get_param('winch/range/max'):
raise ValueError(f'Move aborted: depth {depth} is above max {rospy.get_param("winch/range/max")}')

Expand Down
33 changes: 16 additions & 17 deletions src/phyto_arm/src/arm_chanos.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,30 +53,29 @@ def get_next_task(self, last_task):
else:
raise ValueError(f'Unexpected last task name: {last_task.name}')

# If profiler peak is enabled and ready, execute profiler peak
# Handle continuous movement cases
speed = rospy.get_param('tasks/continuous_speed')
if self.is_downcasting and rospy.get_param('tasks/downcast_type') == 'continuous':
return Task('downcast_continuous', self.start_next_task, rospy.get_param('winch/range/max'), speed)
elif not self.is_downcasting and rospy.get_param('tasks/upcast_type') == 'continuous':
return Task('upcast_continuous', self.start_next_task, rospy.get_param('winch/range/min'), speed)

# If profiler peak is enabled and ready, execute new set of profile steps
if rospy.get_param('tasks/profiler_peak/enabled') and profiler_peak_ready():
self.steps = compute_profiler_steps(self.is_downcasting)
task_name = 'downcast_profile_step' if self.is_downcasting else 'upcast_profile_step'
next_depth = self.steps.pop(0)
return Task(task_name, await_sensor, next_depth)

# If no profiler peak, execute default profile
if self.is_downcasting:
if rospy.get_param('tasks/default_movement/downcast_type') == 'continuous':
speed = rospy.get_param('tasks/default_movement/continuous_speed')
return Task('downcast_continuous', self.start_next_task, rospy.get_param('winch/range/max'), speed)
else:
self.steps = compute_absolute_steps(self.is_downcasting)
next_depth = self.steps.pop(0)
return Task('downcast_step', await_sensor, next_depth)
self.steps = compute_absolute_steps(self.is_downcasting)
next_depth = self.steps.pop(0)
return Task('downcast_step', await_sensor, next_depth)
else:
if rospy.get_param('tasks/default_movement/upcast_type') == 'continuous':
speed = rospy.get_param('tasks/default_movement/continuous_speed')
return Task('upcast_continuous', self.start_next_task, rospy.get_param('winch/range/min'), speed)
else:
self.steps = compute_absolute_steps(self.is_downcasting)
next_depth = self.steps.pop(0)
return Task('upcast_step', await_sensor, next_depth)
self.steps = compute_absolute_steps(self.is_downcasting)
next_depth = self.steps.pop(0)
return Task('upcast_step', await_sensor, next_depth)


# Global reference to arm state
Expand Down Expand Up @@ -119,7 +118,7 @@ def clamp_steps(steps):


def compute_absolute_steps(is_downcast):
steps = rospy.get_param('tasks/default_movement/absolute_steps')
steps = rospy.get_param('tasks/default_steps')
steps = clamp_steps(steps)

# Sort according to direction.
Expand Down

0 comments on commit 8c780b6

Please sign in to comment.