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

Follow nav path #8

Merged
merged 12 commits into from
Jun 27, 2024
Merged
8 changes: 6 additions & 2 deletions src/giskardpy/configs/behavior_tree_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,10 @@ def add_tf_publisher(self, include_prefix: bool = True, tf_topic: str = 'tf',
self.tree.wait_for_goal.publish_state.add_tf_publisher(include_prefix=include_prefix,
tf_topic=tf_topic,
mode=mode)
if god_map.is_standalone():
self.tree.control_loop_branch.publish_state.add_tf_publisher(include_prefix=include_prefix,
tf_topic=tf_topic,
mode=mode)

def add_evaluate_debug_expressions(self):
self.tree.prepare_control_loop.add_compile_debug_expressions()
Expand Down Expand Up @@ -193,9 +197,9 @@ def __init__(self,
"""
self.include_prefix = include_prefix
if is_running_in_pytest():
publish_tf = False
publish_js = False
if god_map.is_in_github_workflow():
publish_js = False
publish_tf = False
debug_mode = False
simulation_max_hz = None
super().__init__(ControlModes.standalone, simulation_max_hz=simulation_max_hz)
Expand Down
23 changes: 16 additions & 7 deletions src/giskardpy/configs/collision_avoidance_config.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
from __future__ import annotations

import abc
from copy import copy
from typing import Dict, Optional, List, Union, DefaultDict, Tuple

from giskardpy.exceptions import SetupException
Expand Down Expand Up @@ -98,13 +99,19 @@ def set_default_external_collision_avoidance(self,
:param hard_threshold: distance threshold not allowed to be violated
:param max_velocity: how fast it will move away from collisions
"""
new_default = CollisionAvoidanceThresholds(
number_of_repeller=number_of_repeller,
soft_threshold=soft_threshold,
hard_threshold=hard_threshold,
max_velocity=max_velocity
)
# overwrite the default of default
old_default = self.collision_scene.collision_avoidance_configs.default_factory()
old_default.external_collision_avoidance.default_factory = lambda: copy(new_default)
self.collision_scene.collision_avoidance_configs.default_factory = lambda: copy(old_default)
# overwrite the defaults of existing entries
for config in self.collision_scene.collision_avoidance_configs.values():
config.external_collision_avoidance.default_factory = lambda: CollisionAvoidanceThresholds(
number_of_repeller=number_of_repeller,
soft_threshold=soft_threshold,
hard_threshold=hard_threshold,
max_velocity=max_velocity
)
config.external_collision_avoidance.default_factory = lambda: copy(new_default)

def overwrite_external_collision_avoidance(self,
joint_name: str,
Expand Down Expand Up @@ -173,7 +180,8 @@ def load_self_collision_matrix(self, path_to_srdf: str, group_name: Optional[str
if group_name not in self.collision_scene.self_collision_matrix_cache:
self.collision_scene.load_self_collision_matrix_from_srdf(path_to_srdf, group_name)
else:
path_to_srdf, self_collision_matrix, disabled_links = self.collision_scene.self_collision_matrix_cache[group_name]
path_to_srdf, self_collision_matrix, disabled_links = self.collision_scene.self_collision_matrix_cache[
group_name]
self.collision_scene.self_collision_matrix = self_collision_matrix
self.collision_scene.disabled_links = disabled_links

Expand Down Expand Up @@ -209,6 +217,7 @@ def setup(self):
def _sanity_check(self):
pass


class DisableCollisionAvoidanceConfig(CollisionAvoidanceConfig):
def __init__(self):
super().__init__(CollisionCheckerLib.none)
Expand Down
4 changes: 2 additions & 2 deletions src/giskardpy/configs/iai_robots/hsr.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,8 +101,8 @@ def __init__(self, drive_joint_name: str = 'brumbrum'):

def setup(self):
self.load_self_collision_matrix('package://giskardpy/self_collision_matrices/iai/hsrb.srdf')
self.set_default_external_collision_avoidance(soft_threshold=0.08,
hard_threshold=0.04)
self.set_default_external_collision_avoidance(soft_threshold=0.05,
hard_threshold=0.0)
self.overwrite_external_collision_avoidance('wrist_roll_joint',
number_of_repeller=4,
soft_threshold=0.05,
Expand Down
21 changes: 21 additions & 0 deletions src/giskardpy/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -242,3 +242,24 @@ class MonitorForceException(ExecutionException):
@GiskardException.register_error_code(GiskardError.BEHAVIOR_TREE_ERROR)
class BehaviorTreeException(GiskardException):
pass


# %% force torque exceptions
@GiskardException.register_error_code(GiskardError.FORCE_TORQUE_MONITOR_ERROR)
class ForceTorqueExceptions(GiskardException):
pass


@GiskardException.register_error_code(GiskardError.FORCE_TORQUE_MONITOR_GRASPING_MISSED_OBJECT)
class ForceTorqueMonitorGraspsingMissedObjectExceptions(GiskardException):
pass


@GiskardException.register_error_code(GiskardError.FORCE_TORQUE_MONITOR_TRANSPORTING_LOST_OBJECT)
class ForceTorqueTransportingLostObjectExceptions(GiskardException):
pass


@GiskardException.register_error_code(GiskardError.FORCE_TORQUE_MONITOR_PLACING_MISSED_PLACING_LOCATION)
class ForceTorquePlacingMissedPlacingLocationExceptions(GiskardException):
pass
Loading
Loading