-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
1 changed file
with
35 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,44 +1,78 @@ | ||
controller_manager: | ||
ros__parameters: | ||
update_rate: 1000 # Hz | ||
# Update rate in Hz. This is the update rate of the controller manager. However, if you don' t configure the update rate for any of the | ||
# controllers, every controller will run at this rate | ||
update_rate: 1000 | ||
# Type configuration for the joint state broadcaster | ||
joint_state_broadcaster: | ||
type: joint_state_broadcaster/JointStateBroadcaster | ||
# Type configuration for the whole body controller | ||
whole_body_controller: | ||
type: wbc_ros/WholeBodyController | ||
# Type configuration for the Cartesian position controller | ||
cartesian_position_controller: | ||
type: wbc_ros/CartesianPositionController | ||
|
||
whole_body_controller: | ||
ros__parameters: | ||
# Control mode of the wbc. Can be one of [velocity,acceleration]. | ||
control_mode: velocity | ||
# Command interfaces to claim from hardware. Can be one of [position,velocity,effort] | ||
command_interfaces: ["position"] | ||
# Names of the tasks to be configured in task configuration. Each task will be a summand in the QP solver's cost function. | ||
task_names: ["ee_pose"] | ||
# The joint weights control the contribution of each individual joint to the solution. Values have to be within [0,1]. | ||
# A zero means here that the joint is not used at all. Size has to be same as number of robot joints. | ||
joint_weights: [1.0,1.0,1.0,1.0,1.0,1.0,1.0] | ||
robot_model: | ||
# Absolute path to plain URDF file of the robot | ||
file: install/wbc_ros/share/wbc_ros/models/urdf/iiwa.urdf | ||
# Robot model type. Must be the exact name of one of the registered robot model plugins. See src/robot_models for all available plugins. Default is rbdl | ||
type: rbdl | ||
tasks: | ||
ee_pose: | ||
# Task type, can be one of 'jnt' (joint space task), 'cart' (Cartesian task) or 'com' (Center of Mass task). | ||
type: cart | ||
# Priority of this task. 0 corresponds to the highest priority. Prioritization is only supported by the hls solver. | ||
priority: 0 | ||
# Only Cartesian tasks: Root frame of the kinematic chain associated with this task. Has to be the name of a valid link in the robot model. | ||
# Only robot_model.type=kdl supports root frames, which are not equal to the root of the URDF tree. | ||
root: world | ||
# Only Cartesian tasks: Tip frame of the kinematic chain associated with this task. Has to be the name of a valid link in the robot model. | ||
tip: tool0 | ||
# Only Cartesian tasks: Reference frame of the task input (frame wrt which the input is expressed). | ||
# This has to be the name of a valid link in robot model. If ref_frame != root the input will be transformed to the root frame. | ||
ref_frame: world | ||
# Initial weights for this task. Size has to be same as number of task variables, e.g. number of joint names in joint space tasks. | ||
# and 6 in case of a Cartesian task. All entries have to be >= 0. Can be used to balance contributions of the task variables. | ||
# A value of 0 means that the reference of the corresponding task variable will be ignored while computing the solution. | ||
weights: [1.0,1.0,1.0,1.0,1.0,1.0] | ||
# Initial activation for this task. Has to be within 0 and 1. Can be used to enable(1)/disable(0) the whole task, | ||
# or to apply a smooth activation function. | ||
activation: 1.0 | ||
solver: | ||
# QP Solver type. Must be the exact name of one of the registered QP solver plugins. See src/solvers for all available plugins. Default is qpoases | ||
type: qpoases | ||
scene: | ||
# Scene type. Must be the exact name of one of the registered scene plugins. See src/scenes for all available plugins. | ||
type: velocity_qp | ||
integrate: true | ||
|
||
cartesian_position_controller: | ||
ros__parameters: | ||
# Control mode of the wbc. Can be one of [velocity,acceleration]. | ||
control_mode: velocity | ||
# Name of the WBC task this controller is assigned to. | ||
task_name: ee_pose | ||
# Node name of the WBC controller. | ||
wbc_name: whole_body_controller | ||
# P-Gain of the controller, size has to be 6. | ||
p_gain: [5.0,5.0,5.0,5.0,5.0,5.0] | ||
# D-Gain of the controller, size has to be 6. In case of velcity control mode, this is the feed forward gain | ||
d_gain: [0.0,0.0,0.0,0.0,0.0,0.0] | ||
# Feed forward gain of the controller, size has to be 6. | ||
ff_gain: [0.0,0.0,0.0,0.0,0.0,0.0] | ||
# Controller output saturation per element. Size has to be 6. | ||
max_control_output: [10.0,10.0,10.0,10.0,10.0,10.0] | ||
# Dead zone for the position error per element. Size has to be 6. | ||
dead_zone: [0.0,0.0,0.0,0.0,0.0,0.0] |