Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/igvc_description/rviz/rviz_settings.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ Visualization Manager:
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_footprint
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
Expand Down
10 changes: 9 additions & 1 deletion src/igvc_description/urdf/robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,22 @@
<xacro:arg name="use_mock_hardware" default="false" />

<link name="base_footprint"/>
<link name="base_link"/>

<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<parent link="base_link"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<child link="part_1"/>
<axis xyz="0 0 1"/>
</joint>

<joint name="footprint_joint" type="fixed">
<parent link="base_link"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<child link="base_footprint"/>
<axis xyz="0 0 1"/>
</joint>

<xacro:include filename="$(find igvc_description)/urdf/model.urdf.xacro"/>
<xacro:include filename="$(find igvc_description)/urdf/sensors.urdf.xacro"/>

Expand Down
2 changes: 1 addition & 1 deletion src/igvc_description/urdf/sensor/camera.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<xacro:include filename="$(find depthai_descriptions)/urdf/depthai_descr.urdf.xacro" />

<joint name="camera_base_joint" type="fixed">
<parent link="base_footprint"/>
<parent link="base_link"/>
<child link="oak_parent"/>
<origin xyz="-0.05 -0.05 0.95" rpy="0 0 ${pi/2}"/>
</joint>
Expand Down
2 changes: 1 addition & 1 deletion src/igvc_description/urdf/sensor/gps.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="navsat_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_footprint"/>
<parent link="base_link"/>
<child link="navsat_link" />
</joint>

Expand Down
2 changes: 1 addition & 1 deletion src/igvc_description/urdf/sensor/imu.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="imu_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_footprint"/>
<parent link="base_link"/>
<child link="imu_link" />
</joint>

Expand Down
2 changes: 1 addition & 1 deletion src/igvc_description/urdf/sensor/lidar.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="laser_joint" type="fixed">
<parent link="base_footprint"/>
<parent link="base_link"/>
<child link="laser_frame"/>
<origin xyz="-0.05 0.605 0.50" rpy="0 0 0"/>
</joint>
Expand Down
2 changes: 1 addition & 1 deletion src/igvc_hardware/config/bot_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ bot_drive_controller:

publish_rate: 50.0 # Hz
odom_frame_id: odom
base_frame_id: base_footprint
base_frame_id: base_link

#TODO These need physical testing
pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
Expand Down
4 changes: 2 additions & 2 deletions src/igvc_nav/config/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ bt_navigator:
ros__parameters:
global_frame: map
robot_base_frame: base_link
odom_topic: /odom
odom_topic: odom
bt_loop_duration: 10
default_server_timeout: 20
wait_for_service_timeout: 1000
Expand Down Expand Up @@ -313,7 +313,7 @@ velocity_smoother:

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
base_frame_id: "base_link"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
Expand Down
4 changes: 2 additions & 2 deletions src/igvc_slam/launch/rtabmap.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ def generate_launch_description():
'depth_topic' : '/camera/camera/aligned_depth_to_color/image_raw',
'rgb_topic' : '/camera/camera/color/image_raw',
'camera_info_topic' : '/camera/camera/color/camera_info',
'frame_id' : 'base_footprint',
'frame_id' : 'base_link',
'publish_tf_odom' : 'true',
'odom_topic' : '/odom',
'odom_topic' : 'odom',
'odom_frame_id' : 'odom',
'approx_sync' : 'true',
'rgbd_sync' : 'true',
Expand Down
4 changes: 2 additions & 2 deletions src/igvc_slam/launch/sim_rtabmap.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@ def generate_launch_description():
'rgb_topic' : '/camera/camera/color/image_raw',
'camera_info_topic' : '/camera/camera/depth/camera_info',
'approx_sync' : 'true',
'frame_id' : 'base_footprint',
'frame_id' : 'base_link',
'log_level' : 'debug',
'publish_tf_odom' : 'true',
'odom_topic' : '/odom',
'odom_topic' : 'odom',
'odom_frame_id' : 'odom',
'sync_queue_size' : '10', #TODO verify
'topic_queue_size' : '10', #TODO verify
Expand Down