--- /dev/null
+# Watch-out: The indentation here is relevant to the semantic!
+
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 100
+
+dynamics_linearizing_controller:
+ type: effort_controllers/DynamicsLinearizingController
+ joints:
+ - left_wheel_joint
+ - right_wheel_joint
+ F: [0.0, 0.08444758509282763, 3.770688129256381, 0.0]
+ G: [2.6468901285322475, 2.6468901285322475, -16.084061415321404, 16.084061415321404]
+ wheel_separation: 0.322
+ wheel_radius: [0.075, 0.075]
+ odom_frame_id: "odom"
+ base_frame_id: "twil_origin"
+ priority: 99
+ time_step: 0.01
--- /dev/null
+# Watch-out: The indentation here is relevant to the semantic!
+
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 100
+
+twist_mrac_linearizing_controller:
+ type: effort_controllers/TwistMracLinearizingController
+ joints:
+ - left_wheel_joint
+ - right_wheel_joint
+ F: [0.0, 0.08444758509282763, 3.770688129256381, 0.0]
+ G: [2.6468901285322475, 2.6468901285322475, -16.084061415321404, 16.084061415321404]
+ Alpha: [10.0, 10.0]
+ wheel_separation: 0.322
+ wheel_radius: [0.075, 0.075]
+ odom_frame_id: "odom"
+ base_frame_id: "twil_origin"
+ priority: 99
+ time_step: 0.01
--- /dev/null
+<launch>
+ <rosparam file="$(find twil_bringup)/config/dynamics_linearizing_controller.yaml" command="load"/>
+
+ <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+ output="screen" args="joint_state_controller dynamics_linearizing_controller"/>
+</launch>
--- /dev/null
+<launch>
+ <rosparam file="$(find twil_bringup)/config/twist_mrac_linearizing_controller.yaml" command="load"/>
+
+ <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+ output="screen" args="joint_state_controller twist_mrac_linearizing_controller"/>
+</launch>