Skip to content
Snippets Groups Projects
Commit 036f09bd authored by Hilario Tome's avatar Hilario Tome
Browse files

Moved the files from talos walking to talos controller configuration

parent e207edb1
No related branches found
No related tags found
No related merge requests found
Showing with 166 additions and 2 deletions
......@@ -10,6 +10,16 @@
<buildtool_depend>catkin</buildtool_depend>
<run_depend>talos_controller_configuration</run_depend>
<run_depend>talos_description</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>tf_lookup</run_depend>
<run_depend>twist_mux</run_depend>
<run_depend>joy</run_depend>
<run_depend>joy_teleop</run_depend>
<run_depend>play_motion</run_depend>
<run_depend>talos_moveit_config</run_depend>
<export>
</export>
......
......@@ -13,7 +13,17 @@ init_offset_controller:
- leg_right_4_joint
- leg_right_5_joint
- leg_right_6_joint
left_ft_sensor: left_ankle_ft
right_ft_sensor: right_ankle_ft
base_imu_sensor: base_imu
hip_spacing_x: -0.03
hip_spacing_y: 0.08
hip_spacing_z: 0.0
femur_length: 0.380
tibia_length: 0.320
foot_height: 0.107
ft_sensor_z: 0.02
config_folder: "$HOME/.pal/init_offset_controller/config"
{leg_left_1_joint: 0.0, leg_left_2_joint: -0.01020865572279723, leg_left_3_joint: -0.05758404462002641,
leg_left_4_joint: 0.0, leg_left_5_joint: 0.05922924786310778, leg_left_6_joint: 0.01595601924646576,
leg_right_1_joint: 0.0, leg_right_2_joint: -0.01020865572279723, leg_right_3_joint: -0.05758404462002641,
leg_right_4_joint: 0.0, leg_right_5_joint: 0.05593884137694505, leg_right_6_joint: 0.008005548225255048}
# Controller to use to move arms while walking. They must expose a FollowJointTrajectory action interface
walk_pose:
controllers:
- right_arm_controller
- left_arm_controller
- head_controller
- torso_controller
joints_rest_pos:
- arm_left_1_joint : 0.34
- arm_left_2_joint : 0.15
- arm_left_3_joint : -0.34
- arm_left_4_joint : -1.0
- arm_left_5_joint : 0.0
- arm_left_6_joint : 0.0
- arm_left_7_joint : 0.0
- arm_right_1_joint: -0.34
- arm_right_2_joint: -0.15
- arm_right_3_joint: 0.34
- arm_right_4_joint: -1.0
- arm_right_5_joint: 0.0
- arm_right_6_joint: 0.0
- arm_right_7_joint: 0.0
- torso_1_joint: 0.0
- torso_2_joint: 0.0
- head_1_joint: 0.0
- head_2_joint: 0.0
joints_to_move:
- arm_left_1_joint: -1.0
- arm_left_3_joint: 1.0
- arm_left_4_joint: 1.0
- arm_right_1_joint: -1.0
- arm_right_3_joint: 1.0
- arm_right_4_joint: 1.0
- torso_2_joint: 0.5
- head_2_joint: 0.5
walking_controller:
type: walking_controller/ReemcControl
joints:
- leg_left_1_joint
- leg_left_2_joint
- leg_left_3_joint
- leg_left_4_joint
- leg_left_5_joint
- leg_left_6_joint
- leg_right_1_joint
- leg_right_2_joint
- leg_right_3_joint
- leg_right_4_joint
- leg_right_5_joint
- leg_right_6_joint
left_ft_sensor: left_ankle_ft
right_ft_sensor: right_ankle_ft
base_imu_sensor: base_imu
check_mode: True
actuators:
- leg_left_1_motor
- leg_left_2_motor
- leg_left_3_motor
- leg_left_4_motor
- leg_left_5_motor
- leg_left_6_motor
- leg_right_1_motor
- leg_right_2_motor
- leg_right_3_motor
- leg_right_4_motor
- leg_right_5_motor
- leg_right_6_motor
loop_counter_factor: -1
debug_backdoor: true
odometry:
enabled : false
vel_window_size: 10
use_imu_yaw : false
publish_rate : 100.0
pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 0.1, 0.1, 0.1]
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 0.1, 0.1, 0.1]
biped_controller:
delta_T: 0.001
ft_sensor_z: 0.02
variable_joint_offset_hip: -0.6
variable_joint_offset_ankle: -0.6
swing_foot_z: 0.03
z_lipm: 0.86
com_stabilizer:
ds_x_p: 0.6
ds_y_p: 0.6
ss_x_p: 0.4
ss_y_p: 0.4
dead_zone: 0.01
foot_offset_clamp: 0.05
hip_offset_x_clamp: 0.05
hip_offset_y_clamp: 0.05
hip_offset_decay: 0.995
hip_spacing_x: -0.03
hip_spacing_y: 0.08
hip_spacing_z: 0.0
femur_length: 0.380
tibia_length: 0.320
foot_height: 0.107
read_absolute_encoders: False
<launch>
<include file="$(find talos_walking)/launch/walking_controller.launch" />
<include file="$(find talos_controller_configuration)/launch/walking_controller.launch" />
<include file="$(find talos_controller_configuration)/launch/upper_body_position_controllers.launch" />
......
<launch>
<!-- init offset controller configuration -->
<rosparam command="load" file="$(find talos_controller_configuration)/config/init_offset_controller.yaml" />
<!-- Spawn init offset controller -->
<node name="init_offset_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="init_offset_controller --stopped" />
</launch>
<launch>
<!-- Walking controller configuration -->
<rosparam command="load" file="$(find talos_controller_configuration)/config/walking_params.yaml" ns="walking_controller" />
<rosparam command="load" file="$(find talos_controller_configuration)/config/walking_controller.yaml" />
<rosparam command="load" file="$(find talos_controller_configuration)/config/offsets.yaml" ns="walking_controller/offsets" />
<!-- Spawn walking controller -->
<node name="walking_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
args="walking_controller" />
</launch>
......@@ -15,6 +15,7 @@
<run_depend>joint_trajectory_controller</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>joint_state_controller</run_depend>
<run_depend>point_head_action</run_depend>
<export>
</export>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment