Skip to content

Commit f4f4fd2

Browse files
authored
Merge branch 'main' into feature/imu_yaw_in_odometry
2 parents 5d4054c + 4f4e46a commit f4f4fd2

File tree

9 files changed

+75
-19
lines changed

9 files changed

+75
-19
lines changed

Makefile

+1-1
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ rosdep:
9090
# Initialize rosdep if not already done
9191
[ -f /etc/ros/rosdep/sources.list.d/20-default.list ] || sudo rosdep init
9292
# Update rosdep and install dependencies from meta directory
93-
rosdep update
93+
rosdep update --include-eol-distros
9494
rosdep install --from-paths . --ignore-src --rosdistro iron -y
9595

9696
status:

bitbots_misc/bitbots_utils/bitbots_utils/utils.py

+22
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,28 @@ def get_parameters_from_other_node(
130130
return results
131131

132132

133+
def get_parameters_from_other_node_sync(
134+
own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0
135+
) -> Dict:
136+
"""
137+
Used to receive parameters from other running nodes. It does not use async internally.
138+
It should not be used in callback functions, but it is a bit more reliable than the async version.
139+
Returns a dict with requested parameter name as dict key and parameter value as dict value.
140+
"""
141+
client = own_node.create_client(GetParameters, f"{other_node_name}/get_parameters")
142+
ready = client.wait_for_service(timeout_sec=service_timeout_sec)
143+
if not ready:
144+
raise RuntimeError(f"Wait for {other_node_name} parameter service timed out")
145+
request = GetParameters.Request()
146+
request.names = parameter_names
147+
response = client.call(request)
148+
149+
results = {} # Received parameter
150+
for i, param in enumerate(parameter_names):
151+
results[param] = parameter_value_to_python(response.values[i])
152+
return results
153+
154+
133155
def set_parameters_of_other_node(
134156
own_node: Node,
135157
other_node_name: str,

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/change_motor_power.py

-9
Original file line numberDiff line numberDiff line change
@@ -21,15 +21,6 @@ def perform(self, reevaluate=False):
2121
raise NotImplementedError
2222

2323

24-
class TurnMotorsOn(AbstractChangeMotorPower):
25-
def perform(self, reevaluate=False):
26-
if not self.blackboard.visualization_active and not self.blackboard.simulation_active:
27-
req = SetBool.Request()
28-
req.data = True
29-
self.blackboard.motor_switch_service.call(req)
30-
return self.pop()
31-
32-
3324
class TurnMotorsOff(AbstractChangeMotorPower):
3425
def perform(self, reevaluate=False):
3526
if not self.blackboard.visualization_active and not self.blackboard.simulation_active:

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/wait.py

+14
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
77
Just waits for something (i.e. that preconditions will be fullfilled)
88
"""
9+
910
from bitbots_hcm.hcm_dsd.actions import AbstractHCMActionElement
1011

1112

@@ -34,3 +35,16 @@ def perform(self, reevaluate=False):
3435
# Pop if the time has elapsed
3536
if self.blackboard.node.get_clock().now().nanoseconds / 1e9 > self.start_time + self.duration:
3637
self.pop()
38+
39+
40+
class WaitRosControlStartDelay(Wait):
41+
"""
42+
The motors need some time to start up,
43+
the time at which we start sending commands is defined in the config of the ros_control node.
44+
This action waits for that time.
45+
"""
46+
47+
def __init__(self, blackboard, dsd, parameters):
48+
super().__init__(blackboard, dsd, parameters)
49+
self.duration = self.blackboard.motor_start_delay
50+
self.blackboard.node.get_logger().info("Waiting for the motors to start up...")

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/decisions/check_hardware.py

+11-2
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ class CheckMotors(AbstractHCMDecisionElement):
1212
def __init__(self, blackboard, dsd, parameters):
1313
super().__init__(blackboard, dsd, parameters)
1414
self.had_problem = False
15+
self.power_was_off = False
1516

1617
def perform(self, reevaluate=False):
1718
self.clear_debug_data()
@@ -71,8 +72,16 @@ def perform(self, reevaluate=False):
7172
# wait for motors to connect
7273
return "PROBLEM"
7374
else:
74-
# we have to turn the motors on
75-
return "TURN_ON"
75+
# The motors are off, so we will not complain
76+
self.power_was_off = True
77+
return "MOTORS_NOT_STARTED"
78+
79+
elif self.power_was_off:
80+
# motors are now on and we can continue
81+
self.blackboard.node.get_logger().info("Motors are now connected. Will resume.")
82+
self.power_was_off = False
83+
# But we want to perform a clean start, so we don't jump directly into the last goal position
84+
return "TURN_ON"
7685

7786
if self.had_problem:
7887
# had problem before, just tell that this is solved now

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm.dsd

+5-2
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,20 @@
11
#EMERGENCY_FALL
22
@RobotStateMotorOff, @CancelGoals, @StopWalking, @PlayAnimationFallingFront, @Wait + time:1 + r:false, @TurnMotorsOff, @Wait
33

4+
#INIT_PATTERN
5+
@RobotStateStartup, @SetTorque + stiff:false + r:false, @WaitRosControlStartDelay + r:false, @SetTorque + stiff:true + r:false, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false
6+
47
-->HCM
58
$StartHCM
69
START_UP --> $Simulation
710
YES --> @RobotStateStartup, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false
8-
NO --> @RobotStateStartup, @Wait + time:1 + r:false, @PlayAnimationStartup, @PlayAnimationDynup + direction:walkready + r:false
11+
NO --> #INIT_PATTERN
912
RUNNING --> $CheckMotors
1013
MOTORS_NOT_STARTED --> @RobotStateStartup, @Wait
1114
OVERLOAD --> #EMERGENCY_FALL
1215
OVERHEAT --> #EMERGENCY_FALL
1316
PROBLEM --> @RobotStateHardwareProblem, @WaitForMotors
14-
TURN_ON --> @TurnMotorsOn, @PlayAnimationDynup + direction:walkready + r:false, @Wait
17+
TURN_ON --> #INIT_PATTERN
1518
OKAY --> $RecordAnimation
1619
RECORD_ACTIVE --> @RobotStateRecord, @Wait
1720
FREE --> $TeachingMode

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py

+6
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
from typing import List, Optional
22

33
import numpy
4+
from bitbots_utils.utils import get_parameters_from_other_node_sync
45
from geometry_msgs.msg import Twist
56
from rclpy.action import ActionClient
67
from rclpy.node import Node
@@ -32,6 +33,11 @@ def __init__(self, node: Node):
3233
self.visualization_active: bool = self.node.get_parameter("visualization_active").value
3334
self.pickup_accel_threshold: float = self.node.get_parameter("pick_up_accel_threshold").value
3435
self.pressure_sensors_installed: bool = self.node.get_parameter("pressure_sensors_installed").value
36+
self.motor_start_delay: int = 0
37+
if not self.simulation_active: # The hardware interface is obviously not available in simulation
38+
self.motor_start_delay = get_parameters_from_other_node_sync(
39+
self.node, "/wolfgang_hardware_interface", ["start_delay"]
40+
)["start_delay"]
3541

3642
# Create service clients
3743
self.foot_zero_service = self.node.create_client(EmptySrv, "set_foot_zero")

bitbots_motion/bitbots_hcm/bitbots_hcm/humanoid_control_module.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ def __init__(self, use_sim_time, simulation_active, visualization_active):
5656
)
5757

5858
# Create own executor for Python part
59-
multi_executor = MultiThreadedExecutor()
59+
multi_executor = MultiThreadedExecutor(num_threads=10)
6060
multi_executor.add_node(self.node)
6161
self.spin_thread = threading.Thread(target=multi_executor.spin, args=(), daemon=True)
6262
self.spin_thread.start()

bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp

+15-4
Original file line numberDiff line numberDiff line change
@@ -858,12 +858,23 @@ void WalkEngine::stepFromOrders(const std::vector<double>& linear_orders, double
858858
// No change in forward step and upward step
859859
tmp_diff.getOrigin()[0] = linear_orders[0];
860860
tmp_diff.getOrigin()[2] = linear_orders[2];
861+
861862
// Add lateral foot offset
862-
if (is_left_support_foot_) {
863-
tmp_diff.getOrigin()[1] = config_.foot_distance;
864-
} else {
865-
tmp_diff.getOrigin()[1] = -1 * config_.foot_distance;
863+
// This is normally just the foot distance, but if we turn we need to also move the foot forward/backward
864+
geometry_msgs::msg::Vector3 foot_offset;
865+
foot_offset.x = -sin(angular_z / 2) * config_.foot_distance;
866+
foot_offset.y = cos(angular_z / 2) * config_.foot_distance;
867+
868+
// Invert lateral offset for right foot
869+
if (!is_left_support_foot_) {
870+
foot_offset.x *= -1;
871+
foot_offset.y *= -1;
866872
}
873+
874+
// Add foot offset to step diff
875+
tmp_diff.getOrigin()[0] += foot_offset.x;
876+
tmp_diff.getOrigin()[1] += foot_offset.y;
877+
867878
// Allow lateral step only on external foot
868879
//(internal foot will return to zero pose)
869880
if ((is_left_support_foot_ && linear_orders[1] > 0.0) || (!is_left_support_foot_ && linear_orders[1] < 0.0)) {

0 commit comments

Comments
 (0)