find_package(twil_description REQUIRED)
find_package(navigation2 REQUIRED)
-install(DIRECTORY config launch rviz
+install(DIRECTORY config launch
DESTINATION share/${PROJECT_NAME}
)
<arg name="controller" value="$(var controller)"/>
</include>
- <node name="rviz" pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share twil_2dnav)/rviz/twil_2dnav.rviz">
+ <node name="rviz" pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share twil_2dnav)/config/twil_2dnav.rviz">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<param name="yaml_filename" value="$(var map)"/>
</node>
- <node pkg="tf2_ros" exec="static_transform_publisher" name="odom_frame_publisher" args="0 0 0 0 0 0 1 map odom"/>
+ <node pkg="tf2_ros" exec="static_transform_publisher" name="odom_frame_publisher" args="--frame-id map --child-frame-id odom"/>
<node pkg="nav2_controller" exec="controller_server" name="controller_server">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param from="$(find-pkg-share twil_2dnav)/config/planner_params.yaml"/>
</node>
+ <!--
<node pkg="nav2_recoveries" exec="recoveries_server" name="recoveries_server">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param from="$(find-pkg-share twil_2dnav)/config/recoveries_params.yaml"/>
<param name="robot_base_frame" value="twil_origin"/>
<remap from="cmd_vel" to="$(var controller)/command"/>
</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"/>
# Watch-out: The indentation here is relevant to the semantic!
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/dynamics_linearizing_controller:
+dynamics_linearizing_controller:
ros__parameters:
joints:
- left_wheel_joint
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/left_wheel_joint_effort_controller:
+left_wheel_joint_effort_controller:
ros__parameters:
joints: [left_wheel_joint]
interface_name: effort
-/right_wheel_joint_effort_controller:
+right_wheel_joint_effort_controller:
ros__parameters:
joints: [right_wheel_joint]
interface_name: effort
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/left_wheel_joint_velocity_controller:
+left_wheel_joint_velocity_controller:
ros__parameters:
joint: left_wheel_joint
pid: {p: 0.0, i: 0.0, d: 0.0}
interface_name: effort
-/right_wheel_joint_velocity_controller:
+right_wheel_joint_velocity_controller:
ros__parameters:
joint: right_wheel_joint
pid: {p: 0.0, i: 0.0, d: 0.0}
# Watch-out: The indentation here is relevant to the semantic!
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/nonsmooth_backstep_controller:
+nonsmooth_backstep_controller:
ros__parameters:
joints:
- left_wheel_joint
# Watch-out: The indentation here is relevant to the semantic!
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/nonsmooth_backstep_controller:
+nonsmooth_backstep_controller:
ros__parameters:
joints:
- left_wheel_joint
# Watch-out: The indentation here is relevant to the semantic!
-/odometry_publisher:
+odometry_publisher:
ros__parameters:
wheel_separation: 0.322
wheel_radius: [0.075, 0.075]
# Watch-out: The indentation here is relevant to the semantic!
-/joint_state_broadcaster:
+joint_state_broadcaster:
ros__parameters:
extra_joints:
- caster_wheel_joint
- front_caster_base_joint
- tower_joint
-/twist_mrac_linearizing_controller:
+twist_mrac_linearizing_controller:
ros__parameters:
joints:
- left_wheel_joint
<remap from="command" to="/$(var controller)/command" />
</node>
- <node pkg="tf2_ros" exec="static_transform_publisher" name="odom_frame_publisher" args="0 0 0 0 0 0 1 map odom" />
+ <node pkg="tf2_ros" exec="static_transform_publisher" name="odom_frame_publisher" args="--frame-id map --child-frame-id odom"/>
<include file="$(find-pkg-share twil_description)/launch/display.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
+ <arg name="gui" value="false"/>
</include>
</launch>
# find dependencies
find_package(ament_cmake REQUIRED)
-install(DIRECTORY config launch meshes rviz xacro
+install(DIRECTORY config launch meshes xacro
DESTINATION share/${PROJECT_NAME}
)
<launch>
<arg name="wam" default="false"/>
- <arg name="use_gui" default="false"/>
+ <arg name="gui" default="false"/>
<arg name="d435" default="false"/>
<arg name="use_sim_time" default="false"/>
- <node pkg="tf2_ros" exec="static_transform_publisher" name="twil_origin_publisher" args="0 0 0 0 0 0 1 map twil_origin" />
- <node if="$(var use_gui)" name="joint_state_publisher" pkg="joint_state_publisher_gui" exec="joint_state_publisher_gui" />
+ <node pkg="tf2_ros" exec="static_transform_publisher" name="twil_origin_publisher" args="--frame-id map --child-frame-id twil_origin" />
+ <node if="$(var gui)" name="joint_state_publisher" pkg="joint_state_publisher_gui" exec="joint_state_publisher_gui" />
<include file="$(find-pkg-share twil_description)/launch/twil.launch.xml">
<arg name="wam" value="$(var wam)" />
<arg name="d435" value="$(var d435)" />
</include>
- <node name="rviz" pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share twil_description)/rviz/display.rviz">
+ <node name="rviz" pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share twil_description)/config/display.rviz">
<param name="use_sim_time" value='$(var use_sim_time)'/>
</node>
</launch>