From 18424f256b8053f9979db31e2d4b05ebf9afc227 Mon Sep 17 00:00:00 2001 From: nathan-gt Date: Wed, 30 Oct 2024 14:45:12 -0400 Subject: [PATCH] Trying to fix udevrules for vectornav Changed velodyne orientation to offset it 180deg. This will probably have an impact in the simulation in gazebo. Adjusted the launch script to stop can bus on exit. Disabled odrive id 24 rr_track (rear right track). Disabled slam_3d to simplify testing. --- src/rove_bringup/config/vn_300.yaml | 2 +- src/rove_bringup/launch/common.launch.py | 6 +++--- src/rove_bringup/launch/real.launch.py | 4 ++-- src/rove_description/urdf/rove.urdf.xacro | 2 +- src/rove_description/urdf/sensor.urdf.xacro | 2 +- src/rove_launch_handler/scripts/launch_script.service | 1 + 6 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/rove_bringup/config/vn_300.yaml b/src/rove_bringup/config/vn_300.yaml index 2935fac..aefe1a3 100644 --- a/src/rove_bringup/config/vn_300.yaml +++ b/src/rove_bringup/config/vn_300.yaml @@ -5,7 +5,7 @@ vectornav: ros__parameters: - port: "/dev/ttyUSB1" # TODO: update this for rove + port: "/dev/ttyUSB0" baud: 921600 adjust_ros_timestamp: True reconnect_ms: 500 diff --git a/src/rove_bringup/launch/common.launch.py b/src/rove_bringup/launch/common.launch.py index 4cb5818..5d29c37 100644 --- a/src/rove_bringup/launch/common.launch.py +++ b/src/rove_bringup/launch/common.launch.py @@ -94,7 +94,7 @@ def generate_launch_description(): launch_arguments={ 'use_sim_time': use_sim_time, "deskewing": "true", - "use_slam3d": "true", + "use_slam3d": "false", }.items(), ) @@ -111,9 +111,9 @@ def generate_launch_description(): robot_state_publisher, robot_localization_node_local, # robot_localization_node_global, - #navsat_transform, + navsat_transform, twist_mux, #rviz, teleop, - #autonomy, + autonomy, ]) diff --git a/src/rove_bringup/launch/real.launch.py b/src/rove_bringup/launch/real.launch.py index 49dcd20..745ef8c 100644 --- a/src/rove_bringup/launch/real.launch.py +++ b/src/rove_bringup/launch/real.launch.py @@ -141,8 +141,8 @@ def create_controller_node(node_name:str): control_node, #TimerAction(period=20.0, actions=[ #gripper, - #vectornav, - #velodyne, + # vectornav, + velodyne, #zed, #]), ]) diff --git a/src/rove_description/urdf/rove.urdf.xacro b/src/rove_description/urdf/rove.urdf.xacro index dec91b8..b5a3744 100644 --- a/src/rove_description/urdf/rove.urdf.xacro +++ b/src/rove_description/urdf/rove.urdf.xacro @@ -51,7 +51,7 @@ - + diff --git a/src/rove_description/urdf/sensor.urdf.xacro b/src/rove_description/urdf/sensor.urdf.xacro index b250f45..116b5c1 100644 --- a/src/rove_description/urdf/sensor.urdf.xacro +++ b/src/rove_description/urdf/sensor.urdf.xacro @@ -78,7 +78,7 @@ - + diff --git a/src/rove_launch_handler/scripts/launch_script.service b/src/rove_launch_handler/scripts/launch_script.service index 57cf45f..cc2b177 100755 --- a/src/rove_launch_handler/scripts/launch_script.service +++ b/src/rove_launch_handler/scripts/launch_script.service @@ -5,6 +5,7 @@ After=network.target [Service] Environment="ROS_LOG_DIR=/var/log/ros2; ROS_DOMAIN_ID=96" ExecStart=/bin/bash -c 'source /media/SSD/stable/rove/install/setup.bash; ip link set can0 up type can bitrate 500000; ros2 launch rove_launch_handler launch_handler.launch.py;' +ExecStop=ip link set can0 down RemainAfterExit=no Restart=on-failure RestartSec=2s