ros__parameters:
frequency: 30.0
two_d_mode: true
- publish_acceleration: true # Whether to publish the acceleration state. Defaults to false if unspecified.
- publish_tf: false # atualmente a tf é publicado pelo twist_mrac e não tem parametro para desativar
+ publish_acceleration: false # Whether to publish the acceleration state. Defaults to false if unspecified.
+ publish_tf: true
map_frame: map
odom_frame: odom
+ # base_link_frame: twil_origin_localization_test
base_link_frame: twil_origin
world_frame: odom
- # config order: (X,Y,Z,roll,pitch,yaw,X˙,Y˙,Z˙,roll˙,pitch˙,yaw˙,X¨,Y¨,Z¨)
+
+ initial_state: [0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0]
# odom0 topic is set on launch file
- odom0_config: [true, true, true,
+ # config order: (X,Y,Z,roll,pitch,yaw,X˙,Y˙,Z˙,roll˙,pitch˙,yaw˙,X¨,Y¨,Z¨)
+ # robot_localization docs recommendation
+ # odom0_config: [false, false, false,
+ # false, false, false,
+ # true, true, false,
+ # false, false, true,
+ # false, false, false]
+ odom0_config: [true, true, false,
+ false, false, true,
false, false, false,
false, false, false,
- false, false, true,
false, false, false]
- imu0: sensor/imu
- imu0_config: [false, false, false,
- true, true, true,
- false, false, false,
- false, false, false,
- false, false, false]
\ No newline at end of file
+
+ # imu0: sensor/imu
+ # robot localization recommendation
+ # imu0_config: [false, false, false,
+ # false, false, true,
+ # false, false, false,
+ # false, false, true,
+ # true, false, false]
+ # nav2 docs recommendation
+ # imu0_config: [false, false, false,
+ # true, true, true,
+ # false, false, false,
+ # false, false, false,
+ # false, false, false]
\ No newline at end of file
<param from="$(find-pkg-share twil_2dnav)/config/behavior_params.yaml"/>
<param name="robot_base_frame" value="twil_origin"/>
<remap from="cmd_vel" to="$(var controller)/command"/>
+ <!-- porque tem dois cmd_vel(aqui e no nav2_controller)?? -->
</node>
<node pkg="nav2_bt_navigator" exec="bt_navigator" name="bt_navigator">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param from="$(find-pkg-share twil_2dnav)/config/bt_navigator_params.yaml"/>
- <param name="robot_base_frame" value="twil_origin"/>
- <remap from="odom" to="$(var controller)/odom"/>
+ <!-- <remap from="odom" to="$(var controller)/odom"/> -->
</node>
<node pkg="robot_localization" exec="ekf_node" name="ekf_filter_node">
<node name="controller_spawner" pkg="controller_manager" exec="spawner"
args="-t effort_controllers/TwistMracLinearizingController -p $(var config) twist_mrac_linearizing_controller"/>
+ <!-- eu queria passar parametros pra esse nodo no launch mas não deu porque os parametros sao passados no arg do comando -->
+ <!-- nao tem como passar esses parametros com um <param from="..."?> -->
+ <!-- nos exemplos do ros_control é usado um ros2_control_node que recebe os parametros... -->
<node name="joint_state_broadcaster_spawner" pkg="controller_manager" exec="spawner"
args="-t joint_state_broadcaster/JointStateBroadcaster -p $(var config) joint_state_broadcaster"/>