Skip to content

Commit

Permalink
Update QEV3D controller configuration: enable chained mode and adjust…
Browse files Browse the repository at this point in the history
… parameter order
  • Loading branch information
bocho0600 committed Feb 9, 2025
1 parent 8312c71 commit 6bab72d
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 6 deletions.
8 changes: 6 additions & 2 deletions src/control/ros2_control/bringup/config/qev3d_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ bicycle_steering_controller:
ros__parameters:
type: bicycle_steering_controller/BicycleSteeringController
# TODO Set up controllers chaining
in_chaied_mode: false
in_chained_mode: true

# Specific parameters of the BicycleSteeringController
wheelbase: 1.580 # distance between the front and rear wheels
Expand Down Expand Up @@ -53,12 +53,15 @@ bicycle_steering_controller:

drive_pid_controller: # The PID Controller for rear-wheel joints
ros__parameters:

type: pid_controller/PidController

in_chained_mode: false
dof_names:
- virtual_rear_wheel_joint # The joint that PID controller will control

# The reference and state interfaces that the PID controller will use
reference_and_state_interfaces: ["position", "velocity"]
reference_and_state_interfaces: ["velocity", "position"] # or we can use ["position"]
command_interface: velocity
gains: # set up the gain for the PID controller to control the rear wheel
virtual_rear_wheel_joint: {p: 30.0, i: 0.0, d: 0.0, antiwindup: true, i_clamp_max: 5.0, i_clamp_min: -5.0}
Expand All @@ -69,6 +72,7 @@ drive_pid_controller: # The PID Controller for rear-wheel joints
steering_pid_controller: # The PID Controller for front-wheel joints
ros__parameters:
type: pid_controller/PidController
in_chained_mode: false
dof_names:
- virtual_front_wheel_joint # The joint that PID controller will control

Expand Down
8 changes: 4 additions & 4 deletions src/control/ros2_control/description/qev3d.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
</hardware>
<joint name="virtual_front_wheel_joint">
<command_interface name="position"/>
<param name = "min">-0.28</param>
<param name = "max">0.28</param>
<!-- <param name = "min">-0.28</param> -->
<!-- <param name = "max">0.28</param> -->
<state_interface name="position"/>
</joint>
<joint name="virtual_rear_wheel_joint">
<command_interface name="velocity"/>
<param name = "min">-10</param>
<param name = "max">10</param>
<!-- <param name = "min">-10</param> -->
<!-- <param name = "max">10</param> -->
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
Expand Down

0 comments on commit 6bab72d

Please sign in to comment.