+++ /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
-
-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 linearizing_controllers)/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>
- <arg name="paused" default="true"/>
- <arg name="headless" default="false"/>
- <arg name="use_sim_time" default="true"/>
- <arg name="wam" default="false"/>
- <arg name="controller" default="twist_mrac"/>
-
- <include file="$(find twil_description)/launch/gazebo.launch" >
- <arg name="paused" value="$(arg paused)"/>
- <arg name="headless" value="$(arg headless)"/>
- <arg name="use_sim_time" value="$(arg use_sim_time)"/>
- <arg name="wam" value="$(arg wam)"/>
- </include>
-
- <include file="$(find linearizing_controllers)/launch/$(arg controller).launch" />
-
-</launch>
+++ /dev/null
-<launch>
- <rosparam file="$(find linearizing_controllers)/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>