forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
vector_gen: Copy *.named_vector sources to *_named_vector.yaml
This will preserve git history through the subsequent commit's changes. (The files are unused as of this commit.)
- Loading branch information
1 parent
a8f75b8
commit 9eb68ab
Showing
16 changed files
with
467 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
namespace: "drake::examples::acrobot" | ||
|
||
element { | ||
name: "tau" | ||
doc: "Torque at the elbow" | ||
doc_units: "Nm" | ||
default_value: "0.0" | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,83 @@ | ||
namespace: "drake::examples::acrobot" | ||
|
||
# Note: default parameter values are taken from: | ||
# Spong, Mark W. "Swing up control of the acrobot." Robotics and Automation, | ||
# 1994. Proceedings., 1994 IEEE International Conference on. IEEE, 1994. | ||
|
||
element { | ||
name: "m1" | ||
doc: "Mass of link 1." | ||
doc_units: "kg" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "m2" | ||
doc: "Mass of link 2." | ||
doc_units: "kg" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "l1" | ||
doc: "Length of link 1." | ||
doc_units: "m" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "l2" | ||
doc: "Length of link 2." | ||
doc_units: "m" | ||
default_value: "2.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "lc1" | ||
doc: "Vertical distance from shoulder joint to center of mass of link 1." | ||
doc_units: "m" | ||
default_value: "0.5" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "lc2" | ||
doc: "Vertical distance from elbow joint to center of mass of link 1." | ||
doc_units: "m" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "Ic1" | ||
doc: "Inertia of link 1 about the center of mass of link 1." | ||
doc_units: "kg*m^2" | ||
default_value: "0.083" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "Ic2" | ||
doc: "Inertia of link 2 about the center of mass of link 2." | ||
doc_units: "kg*m^2" | ||
default_value: "0.33" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "b1" | ||
doc: "Damping coefficient of the shoulder joint." | ||
doc_units: "kg*m^2/s" | ||
default_value: "0.1" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "b2" | ||
doc: "Damping coefficient of the elbow joint." | ||
doc_units: "kg*m^2/s" | ||
default_value: "0.1" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "gravity" | ||
doc: "Gravitational constant." | ||
doc_units: "m/s^2" | ||
default_value: "9.81" | ||
min_value: "0.0" | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,26 @@ | ||
namespace: "drake::examples::acrobot" | ||
|
||
element { | ||
name: "theta1" | ||
doc: "The shoulder joint angle" | ||
doc_units: "rad" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "theta2" | ||
doc: "The elbow joint angle" | ||
doc_units: "rad" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "theta1dot" | ||
doc: "The shoulder joint velocity " | ||
doc_units: "rad/s" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "theta2dot" | ||
doc: "The elbow joint velocity" | ||
doc_units: "rad/s" | ||
default_value: "0.0" | ||
} |
34 changes: 34 additions & 0 deletions
34
examples/acrobot/spong_controller_params_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
namespace: "drake::examples::acrobot" | ||
|
||
# Note: default parameter values are taken from: | ||
# Spong, Mark W. "Swing up control of the acrobot." Robotics and Automation, | ||
# 1994. Proceedings., 1994 IEEE International Conference on. IEEE, 1994. | ||
|
||
element { | ||
name: "k_e" | ||
doc: "Energy shaping gain." | ||
doc_units: "s" | ||
default_value: "5.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "k_p" | ||
doc: "Partial feedback linearization proportional gain." | ||
doc_units: "s^-2" | ||
default_value: "50.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "k_d" | ||
doc: "Partial feedback linearization derivative gain." | ||
doc_units: "s^-1" | ||
default_value: "5.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "balancing_threshold" | ||
doc: "Cost value at which to switch from swing up to balancing." | ||
doc_units: "" | ||
default_value: "1e3" | ||
min_value: "0.0" | ||
} |
26 changes: 26 additions & 0 deletions
26
examples/compass_gait/compass_gait_continuous_state_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,26 @@ | ||
namespace: "drake::examples::compass_gait" | ||
|
||
element { | ||
name: "stance" | ||
doc: "The orientation of the stance leg, measured clockwise from the vertical axis." | ||
doc_units: "radians" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "swing" | ||
doc: "The orientation of the swing leg, measured clockwise from the vertical axis." | ||
doc_units: "radians" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "stancedot" | ||
doc: "The angular velocity of the stance leg." | ||
doc_units: "rad/sec" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "swingdot" | ||
doc: "The angular velocity of the swing leg." | ||
doc_units: "rad/sec" | ||
default_value: "0.0" | ||
} |
45 changes: 45 additions & 0 deletions
45
examples/compass_gait/compass_gait_params_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,45 @@ | ||
namespace: "drake::examples::compass_gait" | ||
|
||
element { | ||
name: "mass_hip" | ||
doc: "Point mass at the hip." | ||
doc_units: "kg" | ||
default_value: "10.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "mass_leg" | ||
doc: "Mass of each leg (modeled as a point mass at the center of mass)." | ||
doc_units: "kg" | ||
default_value: "5.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "length_leg" | ||
doc: "The length of each leg." | ||
doc_units: "m" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "center_of_mass_leg" | ||
doc: "Distance from the hip to the center of mass of each leg." | ||
doc_units: "m" | ||
default_value: ".5" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "gravity" | ||
doc: "An approximate value for gravitational acceleration." | ||
doc_units: "m/s^2" | ||
default_value: "9.81" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "slope" | ||
doc: "The angle of the ramp on which the compass gait is walking. Must have 0 <= slope < PI/2 so that forward == downhill (an assumption used in the foot collision witness function)." | ||
doc_units: "radians" | ||
default_value: "0.0525" | ||
min_value: "0.0" | ||
max_value: "1.5707" | ||
} |
30 changes: 30 additions & 0 deletions
30
examples/multibody/cart_pole/cart_pole_params_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,30 @@ | ||
namespace: "drake::examples::multibody::cart_pole" | ||
|
||
element { | ||
name: "mc" | ||
doc: "Mass of the cart." | ||
doc_units: "kg" | ||
default_value: "10.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "mp" | ||
doc: "Value of the point mass at the end of the pole." | ||
doc_units: "kg" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "l" | ||
doc: "Length of the pole." | ||
doc_units: "m" | ||
default_value: "0.5" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "gravity" | ||
doc: "Standard acceleration due to gravity near Earth's surface." | ||
doc_units: "m/s^2" | ||
default_value: "9.81" | ||
min_value: "0.0" | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
namespace: "drake::examples::pendulum" | ||
|
||
element { | ||
name: "tau" | ||
doc: "Torque at the joint." | ||
doc_units: "Newton-meters" | ||
default_value: "0.0" | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,30 @@ | ||
namespace: "drake::examples::pendulum" | ||
|
||
element { | ||
name: "mass" | ||
doc: "The simple pendulum has a single point mass at the end of the arm." | ||
doc_units: "kg" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "length" | ||
doc: "The length of the pendulum arm." | ||
doc_units: "m" | ||
default_value: "0.5" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "damping" | ||
doc: "The damping friction coefficient relating angular velocity to torque." | ||
doc_units: "kg m^2/s" | ||
default_value: "0.1" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "gravity" | ||
doc: "An approximate value for gravitational acceleration." | ||
doc_units: "m/s^2" | ||
default_value: "9.81" | ||
min_value: "0.0" | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,14 @@ | ||
namespace: "drake::examples::pendulum" | ||
|
||
element { | ||
name: "theta" | ||
doc: "The angle of the pendulum." | ||
doc_units: "radians" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "thetadot" | ||
doc: "The angular velocity of the pendulum." | ||
doc_units: "radians/sec" | ||
default_value: "0.0" | ||
} |
14 changes: 14 additions & 0 deletions
14
examples/rimless_wheel/rimless_wheel_continuous_state_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,14 @@ | ||
namespace: "drake::examples::rimless_wheel" | ||
|
||
element { | ||
name: "theta" | ||
doc: "The orientation of the stance leg, measured clockwise from the vertical axis." | ||
doc_units: "radians" | ||
default_value: "0.0" | ||
} | ||
element { | ||
name: "thetadot" | ||
doc: "The angular velocity of the stance leg." | ||
doc_units: "rad/sec" | ||
default_value: "0.0" | ||
} |
36 changes: 36 additions & 0 deletions
36
examples/rimless_wheel/rimless_wheel_params_named_vector.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,36 @@ | ||
namespace: "drake::examples::rimless_wheel" | ||
|
||
element { | ||
name: "mass" | ||
doc: "The rimless wheel has a single point mass at the hub." | ||
doc_units: "kg" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "length" | ||
doc: "The length of each spoke." | ||
doc_units: "m" | ||
default_value: "1.0" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "gravity" | ||
doc: "An approximate value for gravitational acceleration." | ||
doc_units: "m/s^2" | ||
default_value: "9.81" | ||
min_value: "0.0" | ||
} | ||
element { | ||
name: "number_of_spokes" | ||
doc: "Total number of spokes on the wheel" | ||
doc_units: "integer" | ||
default_value: "8" | ||
min_value: "4" | ||
} | ||
element { | ||
name: "slope" | ||
doc: "The angle of the ramp on which the rimless wheel is walking." | ||
doc_units: "radians" | ||
default_value: "0.08" # produces standing and rolling fixed points | ||
} |
Oops, something went wrong.