--- /dev/null
+# Watch-out: The indentation here is relevant to the semantic!
+
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 100
+
+nonsmooth_backstep_controller:
+ type: effort_controllers/NonSmoothBackstepController
+ 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]
+ lambda: [200.0, 6.0, 6.0, 500.0, 1000.0]
+ gamma: [10.0, 1.0, 10.0, 50.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
+# Watch-out: The indentation here is relevant to the semantic!
+
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 100
+
+nonsmooth_backstep_controller:
+ type: effort_controllers/NonSmoothBackstepController
+ 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]
+ lambda: [200.0, 40.0, 40.0, 500.0, 1000.0]
+ gamma: [10.0, 1.0, 10.0, 50.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>
+ <node name="ident" pkg="twil_ident" type="ident" output="screen">
+ <remap from="ident/dynamic_parameters" to="adaptive_linearizing_controller/dynamic_parameters"/>
+ </node>
+
+ <include file="$(find twil_bringup)/launch/dynamics_linearizing_controller.launch" />
+
+</launch>
--- /dev/null
+<launch>
+
+ <node name="ident" pkg="twil_ident" type="ident" output="screen">
+ <remap from="ident/dynamic_parameters" to="nonsmooth_backstep_controller/dynamic_parameters"/>
+ </node>
+
+ <include file="$(find twil_bringup)/launch/nonsmooth_backstep_controller.launch" />
+
+</launch>
<arg name="wam" value="$(arg wam)"/>
</include>
- <include file="$(find nonsmooth_backstep_controller)/launch/nonsmooth_backstep.launch" />
+ <include file="$(find twil_bringup)/launch/nonsmooth_backstep.launch" />
<node name="eight_trajectory" pkg="pose2d_trajectories" type="eight_trajectory" respawn="false" output="screen" args="_x:=0.0 _y:=-0.5 _radius:=1.0 _ang_vel:=0.1"/>
--- /dev/null
+<launch>
+ <rosparam file="$(find twil_bringup)/config/nonsmooth_backstep_controller.yaml" command="load"/>
+
+ <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
+ output="screen" args="joint_state_controller nonsmooth_backstep_controller"/>
+</launch>