Commit 526fee68 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by olivier stasse

Add ability to control Tiago without the wheels.

parent a1e3a48e
sot_controller:
libname: libsot-tiago-steel-controller.so
libname: libsot-tiago-steel-without-wheels-controller.so
joint_names: [
torso_lift_joint,
arm_1_joint, arm_2_joint, arm_3_joint, arm_4_joint, arm_5_joint, arm_6_joint, arm_7_joint, gripper_finger_joint,
......
......@@ -2,7 +2,6 @@ sot_controller:
libname: libsot-tiago-steel-controller.so
simulation_mode: gazebo
joint_names: [
wheel_left_joint, wheel_right_joint,
torso_lift_joint,
arm_1_joint, arm_2_joint, arm_3_joint, arm_4_joint, arm_5_joint, arm_6_joint, arm_7_joint, gripper_finger_joint,
head_1_joint, head_2_joint ]
......@@ -12,10 +11,6 @@ sot_controller:
control: control
}
control_mode:
wheel_left_joint:
ros_control_mode: VELOCITY
wheel_right_joint:
ros_control_mode: VELOCITY
torso_lift_joint:
ros_control_mode: POSITION
arm_1_joint:
......
sot_controller:
libname: libsot-tiago-steel-without-wheels-controller.so
simulation_mode: gazebo
joint_names: [
wheel_left_joint, wheel_right_joint,
torso_lift_joint,
arm_1_joint, arm_2_joint, arm_3_joint, arm_4_joint, arm_5_joint, arm_6_joint, arm_7_joint, gripper_finger_joint,
head_1_joint, head_2_joint ]
map_rc_to_sot_device: { motor-angles: motor-angles ,
joint-angles: joint-angles, velocities: velocities, forces: forces, currents: currents,
torques: torques, accelerometer_0: accelerometer_0, gyrometer_0: gyrometer_0,
control: control
}
control_mode:
wheel_left_joint:
ros_control_mode: VELOCITY
wheel_right_joint:
ros_control_mode: VELOCITY
torso_lift_joint:
ros_control_mode: POSITION
arm_1_joint:
ros_control_mode: POSITION
arm_2_joint:
ros_control_mode: POSITION
arm_3_joint:
ros_control_mode: POSITION
arm_4_joint:
ros_control_mode: POSITION
arm_5_joint:
ros_control_mode: POSITION
arm_6_joint:
ros_control_mode: POSITION
arm_7_joint:
ros_control_mode: POSITION
gripper_finger_joint:
ros_control_mode: POSITION
head_1_joint:
ros_control_mode: POSITION
head_2_joint:
ros_control_mode: POSITION
dt: 0.001
jitter: 0.0004
......@@ -4,7 +4,7 @@
<!-- Sot Controller configuration -->
<rosparam if="$(arg use_mobile_base)" command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params_with_mobile_base.yaml"/>
<rosparam unless="$(arg use_mobile_base)" command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params.yaml"/>
<rosparam if="$(arg use_mobile_base)" command="load" ns="/sot_controller/velocity_control_pd_motor_init" file="$(find roscontrol_sot_tiago)/config/pids_velocity.yaml"/>
<rosparam if="$(arg use_mobile_base)" command="load" ns="/sot_controller/velocity_control_pd_motor_init" file="$(find roscontrol_sot_tiago)/config/pids_velocity.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_controller.yaml" />
<!-- Spawn walking controller -->
......
<launch>
<arg name="use_mobile_base" default="true"/>
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params_gazebo.yaml"/>
<rosparam command="load" ns="/sot_controller/velocity_control_pd_motor_init" file="$(find roscontrol_sot_tiago)/config/pids_velocity.yaml"/>
<rosparam if="$(arg use_mobile_base)" command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params_gazebo_with_mobile_base.yaml"/>
<rosparam unless="$(arg use_mobile_base)" command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params_gazebo.yaml"/>
<rosparam if="$(arg use_mobile_base)" command="load" ns="/sot_controller/velocity_control_pd_motor_init" file="$(find roscontrol_sot_tiago)/config/pids_velocity.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_controller.yaml" />
<!-- Spawn walking controller -->
<node name="sot_controller_spawner"
pkg="controller_manager" type="spawner" output="screen"
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment