Skip to content

Commit bb38c0e

Browse files
committed
valkyrie files
1 parent 69e8224 commit bb38c0e

File tree

4 files changed

+2193
-0
lines changed

4 files changed

+2193
-0
lines changed

config/valkyrie.json

Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
{
2+
"base_frame": "pelvis",
3+
"point_feet": false,
4+
"foot_frames": {
5+
"0": "leftFoot",
6+
"1": "rightFoot"
7+
},
8+
"model_path": "valkyrie.urdf",
9+
"mass": 127.324,
10+
"g": 9.81,
11+
"joint_rate": 500.0,
12+
"estimate_joint_velocity": true,
13+
"joint_cutoff_frequency": 10.0,
14+
"joint_position_variance": 0.1,
15+
"angular_momentum_cutoff_frequency": 5.0,
16+
"tau_0": 1.0,
17+
"tau_1": 1.0,
18+
"imu_rate": 500.0,
19+
"R_base_to_gyro": [1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, 0.0, -1.0],
20+
"R_base_to_acc": [1.0, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, 0.0, -1.0],
21+
"calibrate_imu": false,
22+
"max_imu_calibration_cycles": 300,
23+
"bias_acc": [0.0, 0.0, 0.0],
24+
"bias_gyro": [0.0, 0.0, 0.0],
25+
"gyro_cutoff_frequency": 5.0,
26+
"force_torque_rate": 500.0,
27+
"R_foot_to_force": {
28+
"0": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0],
29+
"1": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
30+
},
31+
"R_foot_to_torque": {
32+
"0": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0],
33+
"1": [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
34+
},
35+
"attitude_estimator_proportional_gain": 0.02,
36+
"attitude_estimator_integral_gain": 0.0,
37+
"estimate_contact_status": true,
38+
"high_threshold": 350.0,
39+
"low_threshold": 125.0,
40+
"median_window": 13,
41+
"outlier_detection": false,
42+
"convergence_cycles": 0,
43+
"imu_angular_velocity_covariance": [1e-4, 1e-4, 1e-4],
44+
"imu_angular_velocity_bias_covariance": [1e-6, 1e-6, 1e-6],
45+
"imu_linear_acceleration_covariance": [1e-3, 1e-3, 1e-3],
46+
"imu_linear_acceleration_bias_covariance": [1e-5, 1e-5, 1e-5],
47+
"contact_position_covariance": [1e-6, 1e-6, 1e-6],
48+
"contact_orientation_covariance": [1e-3, 1e-3, 1e-3],
49+
"contact_position_slip_covariance": [1e-4, 1e-4, 1e-4],
50+
"contact_orientation_slip_covariance": [1e-3, 1e-3, 1e-3],
51+
"com_position_process_covariance": [1e-6, 1e-6, 1e-6],
52+
"com_linear_velocity_process_covariance": [1e-4, 1e-4, 1e-4],
53+
"external_forces_process_covariance": [1e-2, 1e-2, 1e-2],
54+
"com_position_covariance": [1e-6, 1e-6, 1e-6],
55+
"com_linear_acceleration_covariance": [1e-3, 1e-3, 1e-3],
56+
"initial_base_position_covariance": [1.0, 1.0, 1.0],
57+
"initial_base_orientation_covariance": [1.0, 1.0, 1.0],
58+
"initial_base_linear_velocity_covariance": [1.0, 1.0, 1.0],
59+
"initial_contact_position_covariance": [1.0, 1.0, 1.0],
60+
"initial_contact_orientation_covariance": [1.0, 1.0, 1.0],
61+
"initial_imu_linear_acceleration_bias_covariance": [1.0, 1.0, 1.0],
62+
"initial_imu_angular_velocity_bias_covariance": [1.0, 1.0, 1.0],
63+
"initial_com_position_covariance": [1.0, 1.0, 1.0],
64+
"initial_com_linear_velocity_covariance": [1.0, 1.0, 1.0],
65+
"initial_external_forces_covariance": [1.0, 1.0, 1.0],
66+
"T_base_to_odom": [1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0],
67+
"is_flat_terrain": false,
68+
"terrain_height_covariance": 1e-3
69+
}

serow_ros/config/valkyrie.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
joint_state_rate: 500
2+
joint_state_topic: "/ihmc_ros/valkyrie/output/joint_states"
3+
base_imu_topic: "/ihmc_ros/valkyrie/output/imu/pelvis_pelvisMiddleImu"
4+
config_file_path: "valkyrie.json"
5+
force_torque_state_topics:
6+
- "/ihmc_ros/valkyrie/output/foot_force/left"
7+
- "/ihmc_ros/valkyrie/output/foot_force/right"
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
<launch>
2+
<rosparam file="$(find serow_ros)/config/valkyrie.yaml" command="load" />
3+
<node name="serow_ros" pkg="serow_ros" type="serow_driver" output="screen" />
4+
</launch>

0 commit comments

Comments
 (0)