Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Stack Of Tasks
tiago_metapkg_ros_control_sot
Commits
a1e3a48e
Commit
a1e3a48e
authored
Aug 06, 2019
by
Joseph Mirabel
Committed by
olivier stasse
Aug 08, 2019
Browse files
Add ability to ignore the mobile base.
parent
0126af89
Changes
3
Hide whitespace changes
Inline
Side-by-side
roscontrol_sot_tiago/config/sot_tiago_params.yaml
View file @
a1e3a48e
sot_controller
:
libname
:
libsot-tiago-steel-controller.so
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
]
...
...
@@ -11,10 +10,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
:
...
...
roscontrol_sot_tiago/config/sot_tiago_params_with_mobile_base.yaml
0 → 100644
View file @
a1e3a48e
sot_controller
:
libname
:
libsot-tiago-steel-controller.so
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
roscontrol_sot_tiago/launch/sot_tiago_controller.launch
View file @
a1e3a48e
<launch>
<arg name="use_mobile_base" default="true"/>
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_params.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_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 command="load" file="$(find roscontrol_sot_tiago)/config/sot_tiago_controller.yaml" />
<!-- Spawn walking controller -->
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment