Skip to content
GitLab
Projects
Groups
Snippets
Help
Loading...
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
T
talos-metapkg-ros-control-sot
Project overview
Project overview
Details
Activity
Releases
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Issues
1
Issues
1
List
Boards
Labels
Service Desk
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Operations
Operations
Incidents
Environments
Packages & Registries
Packages & Registries
Container Registry
Analytics
Analytics
CI / CD
Repository
Value Stream
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Stack Of Tasks
talos-metapkg-ros-control-sot
Commits
23b22d0e
Commit
23b22d0e
authored
Nov 16, 2018
by
Olivier Stasse
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Update params file to handle new structure of roscontrol_sot
parent
d05ec5bc
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
107 additions
and
9 deletions
+107
-9
roscontrol_sot_talos/config/sot_talos_params.yaml
roscontrol_sot_talos/config/sot_talos_params.yaml
+1
-2
roscontrol_sot_talos/config/sot_talos_params_control_mode.yaml
...ntrol_sot_talos/config/sot_talos_params_control_mode.yaml
+34
-0
roscontrol_sot_talos/config/sot_talos_params_control_mode_effort.yaml
...ot_talos/config/sot_talos_params_control_mode_effort.yaml
+35
-0
roscontrol_sot_talos/config/sot_talos_params_effort.yaml
roscontrol_sot_talos/config/sot_talos_params_effort.yaml
+1
-2
roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
+3
-2
roscontrol_sot_talos/config/sot_talos_params_gazebo_effort.yaml
...trol_sot_talos/config/sot_talos_params_gazebo_effort.yaml
+29
-3
roscontrol_sot_talos/launch/sot_talos_controller.launch
roscontrol_sot_talos/launch/sot_talos_controller.launch
+1
-0
roscontrol_sot_talos/launch/sot_talos_controller_effort.launch
...ntrol_sot_talos/launch/sot_talos_controller_effort.launch
+1
-0
roscontrol_sot_talos/launch/sot_talos_controller_gazebo.launch
...ntrol_sot_talos/launch/sot_talos_controller_gazebo.launch
+1
-0
roscontrol_sot_talos/launch/sot_talos_controller_gazebo_effort.launch
...ot_talos/launch/sot_talos_controller_gazebo_effort.launch
+1
-0
No files found.
roscontrol_sot_talos/config/sot_talos_params.yaml
View file @
23b22d0e
...
...
@@ -8,7 +8,7 @@ sot_controller:
]
map_rc_to_sot_device
:
{
motor-angles
:
motor-angles
,
joint-angles
:
joint-angles
,
velocities
:
velocities
,
forces
:
forces
,
currents
:
currents
,
torques
:
torques
,
c
md-joints
:
control
,
cmd-effort
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
torques
:
torques
,
c
ontrol
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
position_control_init_pos
:
-
name
:
leg_left_1_joint
des_pos
:
0.0
...
...
@@ -74,7 +74,6 @@ sot_controller:
des_pos
:
0.0
-
name
:
head_2_joint
des_pos
:
0.0
control_mode
:
POSITION
dt
:
0.001
jitter
:
0.0004
roscontrol_sot_talos/config/sot_talos_params_control_mode.yaml
0 → 100644
View file @
23b22d0e
sot_controller
:
control_mode
:
arm_left_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_3_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_4_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_5_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_6_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_left_7_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_3_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_4_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_5_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_6_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
arm_right_7_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
gripper_left_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
gripper_right_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
head_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
head_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
leg_left_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_left_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_left_3_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_left_4_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_left_5_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_left_6_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_3_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_4_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_5_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
leg_right_6_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
torso_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
torso_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
VELOCITY
}
\ No newline at end of file
roscontrol_sot_talos/config/sot_talos_params_control_mode_effort.yaml
0 → 100644
View file @
23b22d0e
sot_controller
:
control_mode
:
arm_left_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_left_7_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
arm_right_7_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
gripper_left_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
gripper_right_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
head_1_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
head_2_joint
:
{
ros_control_mode
:
POSITION
,
sot_control_mode
:
POSITION
}
leg_left_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
torso_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
torso_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
\ No newline at end of file
roscontrol_sot_talos/config/sot_talos_params_effort.yaml
View file @
23b22d0e
...
...
@@ -8,7 +8,6 @@ sot_controller:
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
,
cmd-joints
:
control
,
cmd-effort
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
control_mode
:
EFFORT
torques
:
torques
,
control
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
dt
:
0.001
jitter
:
0.0004
roscontrol_sot_talos/config/sot_talos_params_gazebo.yaml
View file @
23b22d0e
...
...
@@ -9,7 +9,7 @@ sot_controller:
]
map_rc_to_sot_device
:
{
motor-angles
:
motor-angles
,
joint-angles
:
joint-angles
,
velocities
:
velocities
,
forces
:
forces
,
currents
:
currents
,
torques
:
torques
,
c
md-joints
:
control
,
cmd-effort
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
torques
:
torques
,
c
ontrol
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
position_control_init_pos
:
-
name
:
leg_left_1_joint
des_pos
:
0.0
...
...
@@ -75,6 +75,7 @@ sot_controller:
des_pos
:
0.0
-
name
:
head_2_joint
des_pos
:
0.0
control_mode
:
POSITION
dt
:
0.001
jitter
:
0.0004
verbosity_level
:
5
\ No newline at end of file
roscontrol_sot_talos/config/sot_talos_params_gazebo_effort.yaml
View file @
23b22d0e
...
...
@@ -9,6 +9,32 @@ sot_controller:
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
,
cmd-joints
:
control
,
cmd-effort
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
control_mode
:
EFFORT
dt
:
0.001
torques
:
torques
,
control
:
control
,
accelerometer_0
:
accelerometer_0
,
gyrometer_0
:
gyrometer_0
}
control_mode
:
leg_left_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_left_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_1_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_2_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_3_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_4_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_5_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
leg_right_6_joint
:
{
ros_control_mode
:
EFFORT
,
sot_control_mode
:
EFFORT
}
dt
:
0.001
roscontrol_sot_talos/launch/sot_talos_controller.launch
View file @
23b22d0e
...
...
@@ -2,6 +2,7 @@
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<!-- Spawn walking controller -->
...
...
roscontrol_sot_talos/launch/sot_talos_controller_effort.launch
View file @
23b22d0e
...
...
@@ -2,6 +2,7 @@
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_effort.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode_effort.yaml"/>
<rosparam command="load" ns="/sot_controller/effort_control_pd_motor_init" file="$(find roscontrol_sot_talos)/config/pids_effort.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
...
...
roscontrol_sot_talos/launch/sot_talos_controller_gazebo.launch
View file @
23b22d0e
...
...
@@ -3,6 +3,7 @@
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_gazebo.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode.yaml"/>
<!-- Spawn walking controller -->
<node name="sot_controller_spawner"
...
...
roscontrol_sot_talos/launch/sot_talos_controller_gazebo_effort.launch
View file @
23b22d0e
...
...
@@ -2,6 +2,7 @@
<!-- Sot Controller configuration -->
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_gazebo_effort.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_params_control_mode_effort.yaml"/>
<rosparam command="load" ns="/sot_controller/effort_control_pd_motor_init" file="$(find talos_hardware_gazebo)/config/pids.yaml"/>
<rosparam command="load" file="$(find roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
...
...
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