Description
Hi guys, I'm really enjoying the fruits of your hard work. I've successfully run the openshc stack on my custom hexapod (video here: https://www.youtube.com/watch?v=gDRpkwpoU_c). It has 18 Dynamixel RX28 servos, and runs on a Jetson Nano.
I've been trying to wrap my head around the admittance controller feature of the openshc stack. Here is my understanding of what it does: it can either calculate the force at the tip from the servos' load feedback, or measure them directly through additional sensors. While walking, when a leg touches (i.e. tip force > threshold) the ground earlier or later than expected (as it would on a flat surface), it will hold the z position of that leg, so that 1) not one leg bears too much load and 2) to try to keep the body relatively level.
At first I tried playing around with the parameters for the admittance controller with use_joint_effort
set to true
, but it didn't seem to have any effect on the walking behaviour. I had a brief look at the code for how it's calculated, and it seems it's only initialized to zero vectors here
syropod_highlevel_controller/src/model.cpp
Line 182 in 26c0c71
The next thing I tried was to implement a simple "force" sensor using tactile push button switches attached to the feet. I attached them to an arduino that communicates with the host system through serial, and wrote a little ROS node that publishes the tip sensor data to the topic /tip_states
. I tried publishing them at 100Hz and 1000Hz. Since it's just a push button switch, the published message looks like this with only the z component of the force being nonzero:
header:
seq: 542
stamp:
secs: 1598803970
nsecs: 978107929
frame_id: ''
name:
- AR_
- BR_
- CR_
- CL_
- BL_
- AL_
wrench:
-
force:
x: 0.0
y: 0.0
z: 0.0
torque:
x: 0.0
y: 0.0
z: 0.0
-
force:
x: 0.0
y: 0.0
z: 1.0
torque:
x: 0.0
y: 0.0
z: 0.0
-
force:
x: 0.0
y: 0.0
z: 0.0
torque:
x: 0.0
y: 0.0
z: 0.0
-
force:
x: 0.0
y: 0.0
z: 1.0
torque:
x: 0.0
y: 0.0
z: 0.0
-
force:
x: 0.0
y: 0.0
z: 0.0
torque:
x: 0.0
y: 0.0
z: 0.0
-
force:
x: 0.0
y: 0.0
z: 1.0
torque:
x: 0.0
y: 0.0
z: 0.0
step_plane: []
- The values in the field
name
are chosen so that will correctly recognize them. - I wasn't sure how to construct the
step_plane
values, so I left them empty. - the
wrench.force.z
is set to 1 if the tip switch is pressed and 0 when not.
In my understanding, this should be sufficient to get that part of the code rolling, but it still doesn't seem to be doing what I think it's supposed to be doing. For example, it does these little "jumps" when stepping onto obstacles about 5cm tall, like you can see around 0:12 on the video (https://youtu.be/gDRpkwpoU_c?t=12).
Any pointers would be appreciated.
Cheers!