champ
champ copied to clipboard
Default robot stance too narrow
Greetings, I am trying to configure a custom robot (ANYmal D) using the champ framework. I am using the ANYmal C base parameters for gait, links and so on, and put the ANYmal D urdf on top of it. After modifying the PID parameters a little bit, I could get an initial controller that manages to make the robot walk for some time.
My problem is that the robot quickly loses its balance when walking. I suspect this is due to the default stance being too narrow, resulting in a small support polygon.
I would like to know if there is any straightforward way of configuring this parameter,. I checked the gait configuration and experimented a bit with it, but to no avail.
Thanks in advance.
Stance width is a kind of double edged sword. Wider gives a larger polygon when standing on all four legs, but as soon as the robot walks, the “polygon” becomes a “line" with zero width. Assume the case of walking straight forward. The robot translates forward relative to the suport “line”. And the center of gravity moves left or right relative top the line. A smaller stance with means there is less leteral movment of the CG relative to the line.
There is an optimal stance wiidth and it seems to be to chance. You want it to be wide when stopped of moving VERY slow and narrow as speed picks up.
I have a real dog and I watch her in a Trott, she keeps her legs apart only enough so the feet don't collide. This has the effect of making the “support line” nearly parallel with the direction of movement. This minimizes lateral balance shift durring the stride.
When she goes even faster she switches to a gallop where the front and back legs move together. In this case the “suport line” is at 90 degrees to the motion and there is zero lateral balance shift.
I tried to get my robot to use a wide stance and it requires some odd sideways leg motion to keeep the CG over the line, Narow stances don’require this.
In short, as soon as the robot lifts two legs off the ground, the polygon vanishes and you have zero static stability. The ‘bot becomes an inverted pendulum.
On May 7, 2025, at 10:13 AM, luisemilio14 @.***> wrote:
luisemilio14 created an issue (chvmp/champ#155) https://github.com/chvmp/champ/issues/155 Greetings, I am trying to configure a custom robot (ANYmal D) using the champ framework. I am using the ANYmal C base parameters for gait, links and so on, and put the ANYmal D urdf on top of it. After modifying the PID parameters a little bit, I could get an initial controller that manages to make the robot walk for some time.
My problem is that the robot quickly loses its balance when walking. I suspect this is due to the default stance being too narrow, resulting in a small support polygon.
Screenshot.from.2025-05-07.14-09-43.png (view on web) https://github.com/user-attachments/assets/2284c796-f2fe-4a6a-b382-a823f7d3a8a6 I would like to know if there is any straightforward way of configuring this parameter,. I checked the gait configuration and experimented a bit with it, but to no avail.
Thanks in advance.
— Reply to this email directly, view it on GitHub https://github.com/chvmp/champ/issues/155, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABQKNRRIPV2WYJ5L7NZUQQT25I5NDAVCNFSM6AAAAAB4UOABOGVHI2DSMVQWIX3LMV43ASLTON2WKOZTGA2DMNRUHE4DEOI. You are receiving this because you are subscribed to this thread.
Thanks for the insight! Do you have any tips on how I can modify the robot parameters in order to get a more stable locomotion pattern? I really hope it does not come down to trial-and-error tuning of the PID parameters...
I am having the same same problem with my my robot, inspired by mevius. Were you able to find a solution?
I noticed my controller was actually using an effort controller instead of a position controller. After changing it, I could get the robot to move with default configuration. Here's the file:
controller_manager:
ros__parameters:
use_sim_time: True
update_rate: 30 # Hz
# joint_states_controller:
# type: joint_state_broadcaster/JointStateBroadcaster
# joint_group_effort_controller:
# type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
ros__parameters:
type: joint_state_broadcaster/JointStateBroadcaster
# publish_rate: 30
joint_group_effort_controller:
ros__parameters:
use_sim_time: True
type: joint_trajectory_controller/JointTrajectoryController
joints:
- LF_HAA
- LF_HFE
- LF_KFE
- RF_HAA
- RF_HFE
- RF_KFE
- LH_HAA
- LH_HFE
- LH_KFE
- RH_HAA
- RH_HFE
- RH_KFE
command_interfaces:
- effort
- position
state_interfaces:
- position
- velocity
gains:
LF_HAA : {p: 500.0, i: 50.0, d: 30.0}
LF_HFE : {p: 500.0, i: 50.0, d: 30.0}
LF_KFE : {p: 500.0, i: 50.0, d: 30.0}
RF_HAA : {p: 500.0, i: 50.0, d: 30.0}
RF_HFE : {p: 500.0, i: 50.0, d: 30.0}
RF_KFE : {p: 500.0, i: 50.0, d: 30.0}
LH_HAA : {p: 500.0, i: 50.0, d: 30.0}
LH_HFE : {p: 500.0, i: 50.0, d: 30.0}
LH_KFE : {p: 500.0, i: 50.0, d: 30.0}
RH_HAA : {p: 500.0, i: 50.0, d: 30.0}
RH_HFE : {p: 500.0, i: 50.0, d: 30.0}
RH_KFE : {p: 500.0, i: 50.0, d: 30.0}
After doing so, the robot was able to move smoothly. Note there wasn't an apparent change in stance width, which implies this was not actually the issue. Rather, the controller needs to be configured for correct operation.
Thanks for the reply.
Regarding the controller I had the opposite situation. I started setting the controller for position and the robot was "exploding" in simulation since the joints were moving instantly to the requested position. The problem was solved using effot controller.
About the stance width I was able to solve the problem. Apparently CHAMP, in the default stand position, tries to align the Upper Leg Link and The Foot Link. My problem was that in the URDF both links were displaced. Once I aligned them vertically, the problem was solved.
@LucasC19 thanks for the suggestion, I might try it out in other robots.